From 25eeb878683f1cca74f6a86af6cf7b97542d45e2 Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 10:56:07 -0700 Subject: [PATCH 1/7] Apply windows vibility fix changes Signed-off-by: Devin Bonnie --- CMakeLists.txt | 51 ++++++++++--------- .../collector/collector.hpp | 14 ++++- .../collector/generate_statistics_message.hpp | 2 + .../collector/metric_details_interface.hpp | 4 +- .../moving_average.hpp | 29 ++++++++--- .../moving_average_statistics/types.hpp | 5 +- .../received_message_age.hpp | 6 +-- .../topic_statistics_collector.hpp | 1 + .../visibility_control.hpp | 46 +++++++++++++++++ 9 files changed, 119 insertions(+), 39 deletions(-) create mode 100644 include/libstatistics_collector/visibility_control.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index c9fa3a9..eb5c140 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ endif() # Enable strict compiler flags if possible. include(CheckCXXCompilerFlag) set(FLAGS -pedantic -Wno-long-long -Wall -Wextra -Wcast-qual -Wformat -Wwrite-strings -Wcast-align - -Wno-error=cast-align -Wmissing-declarations) + -Wno-error=cast-align -Wmissing-declarations -Wconversion) foreach(FLAG ${FLAGS}) check_cxx_compiler_flag(${FLAG} R${FLAG}) if(${R${FLAG}}) @@ -28,29 +28,39 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) +find_package(statistics_msgs REQUIRED) find_package(rcl REQUIRED) find_package(rcpputils REQUIRED) find_package(rosidl_default_generators REQUIRED) -find_package(statistics_msgs REQUIRED) find_package(std_msgs REQUIRED) -rosidl_generate_interfaces(libstatistics_collector_test_msgs - "test/msg/DummyMessage.msg" - DEPENDENCIES "std_msgs" -) - -include_directories(include) +include_directories("include") +include_directories("${CMAKE_CURRENT_BINARY_DIR}/include") -add_library(${PROJECT_NAME} SHARED +add_library(${PROJECT_NAME} src/libstatistics_collector/collector/collector.cpp src/libstatistics_collector/collector/generate_statistics_message.cpp src/libstatistics_collector/moving_average_statistics/moving_average.cpp src/libstatistics_collector/moving_average_statistics/types.cpp) +target_compile_definitions(${PROJECT_NAME} PRIVATE "LIBSTATISTICS_COLLECTOR_BUILDING_LIBRARY") + ament_target_dependencies(${PROJECT_NAME} + "statistics_msgs" "rcl" - "rcpputils" - "statistics_msgs") + "rcpputils") + +install( + TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) +ament_export_dependencies("statistics_msgs" "rcl" "rcpputils" "rosidl_default_runtime") if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) @@ -77,25 +87,18 @@ if(BUILD_TESTING) test/topic_statistics_collector/test_received_message_age.cpp) target_link_libraries(test_received_message_age ${PROJECT_NAME}) ament_target_dependencies(test_received_message_age "rcl" "rcpputils") -endif() -# To enable use of dummy_message.hpp in test_received_message_age -rosidl_target_interfaces(test_received_message_age libstatistics_collector_test_msgs "rosidl_typesupport_cpp") + rosidl_generate_interfaces(libstatistics_collector_test_msgs + "test/msg/DummyMessage.msg" + DEPENDENCIES "std_msgs") -install( - TARGETS "${PROJECT_NAME}" - EXPORT "${PROJECT_NAME}-targets" - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) + # To enable use of dummy_message.hpp in test_received_message_age + rosidl_target_interfaces(test_received_message_age libstatistics_collector_test_msgs "rosidl_typesupport_cpp") +endif() install( DIRECTORY include/ DESTINATION include ) -ament_export_dependencies(rcl rcpputils rosidl_default_runtime) -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) - ament_package() diff --git a/include/libstatistics_collector/collector/collector.hpp b/include/libstatistics_collector/collector/collector.hpp index 656d8ef..d4813b1 100644 --- a/include/libstatistics_collector/collector/collector.hpp +++ b/include/libstatistics_collector/collector/collector.hpp @@ -18,9 +18,11 @@ #include #include +#include "metric_details_interface.hpp" + +#include "libstatistics_collector/visibility_control.hpp" #include "libstatistics_collector/moving_average_statistics/moving_average.hpp" #include "libstatistics_collector/moving_average_statistics/types.hpp" -#include "metric_details_interface.hpp" #include "rcpputils/thread_safety_annotations.hpp" @@ -35,7 +37,10 @@ namespace collector class Collector : public MetricDetailsInterface { public: + LIBSTATISTICS_COLLECTOR_PUBLIC Collector() = default; + + LIBSTATISTICS_COLLECTOR_PUBLIC virtual ~Collector() = default; /** @@ -44,6 +49,7 @@ class Collector : public MetricDetailsInterface * * @param the measurement observed */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual void AcceptData(const double measurement); /** @@ -51,11 +57,13 @@ class Collector : public MetricDetailsInterface * * @return the StatisticData for all the observed measurements */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual moving_average_statistics::StatisticData GetStatisticsResults() const; /** * Clear / reset all current measurements. */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual void ClearCurrentMeasurements(); /** @@ -63,6 +71,7 @@ class Collector : public MetricDetailsInterface * * @return the started state of this collector */ + LIBSTATISTICS_COLLECTOR_PUBLIC bool IsStarted() const; /** @@ -70,6 +79,7 @@ class Collector : public MetricDetailsInterface * * @return a string detailing the current status */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual std::string GetStatusString() const; // TODO(dabonnie): uptime (once start has been called) @@ -81,6 +91,7 @@ class Collector : public MetricDetailsInterface * * @return true if started, false if an error occurred */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual bool Start(); /** @@ -92,6 +103,7 @@ class Collector : public MetricDetailsInterface * * @return true if stopped, false if an error occurred */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual bool Stop(); private: diff --git a/include/libstatistics_collector/collector/generate_statistics_message.hpp b/include/libstatistics_collector/collector/generate_statistics_message.hpp index 6c41b4c..fe1d0b8 100644 --- a/include/libstatistics_collector/collector/generate_statistics_message.hpp +++ b/include/libstatistics_collector/collector/generate_statistics_message.hpp @@ -20,6 +20,7 @@ #include "builtin_interfaces/msg/time.hpp" #include "statistics_msgs/msg/metrics_message.hpp" +#include "libstatistics_collector/visibility_control.hpp" #include "libstatistics_collector/moving_average_statistics/types.hpp" namespace libstatistics_collector @@ -38,6 +39,7 @@ namespace collector * @param data statistics derived from the measurements made in the window * @return a MetricsMessage containing the statistics in the data parameter */ +LIBSTATISTICS_COLLECTOR_PUBLIC statistics_msgs::msg::MetricsMessage GenerateStatisticMessage( const std::string & node_name, const std::string & metric_name, diff --git a/include/libstatistics_collector/collector/metric_details_interface.hpp b/include/libstatistics_collector/collector/metric_details_interface.hpp index 5f8f0ea..dbd568c 100644 --- a/include/libstatistics_collector/collector/metric_details_interface.hpp +++ b/include/libstatistics_collector/collector/metric_details_interface.hpp @@ -17,6 +17,8 @@ #include +#include "libstatistics_collector/visibility_control.hpp" + namespace libstatistics_collector { namespace collector @@ -26,7 +28,7 @@ namespace collector * Interface to represent a single metric's name and unit, * which are used for metric message generation and publication. */ -class MetricDetailsInterface +class LIBSTATISTICS_COLLECTOR_PUBLIC MetricDetailsInterface { public: virtual ~MetricDetailsInterface() = default; diff --git a/include/libstatistics_collector/moving_average_statistics/moving_average.hpp b/include/libstatistics_collector/moving_average_statistics/moving_average.hpp index a2f7c27..7e5bca6 100644 --- a/include/libstatistics_collector/moving_average_statistics/moving_average.hpp +++ b/include/libstatistics_collector/moving_average_statistics/moving_average.hpp @@ -25,6 +25,8 @@ #include "types.hpp" +#include "libstatistics_collector/visibility_control.hpp" + #include "rcpputils/thread_safety_annotations.hpp" namespace libstatistics_collector @@ -43,32 +45,38 @@ namespace moving_average_statistics * for standard deviation. * * When statistics are not available, e.g. no observations have been made, NaNs are returned. -**/ + */ class MovingAverageStatistics { public: + LIBSTATISTICS_COLLECTOR_PUBLIC MovingAverageStatistics() = default; + + LIBSTATISTICS_COLLECTOR_PUBLIC ~MovingAverageStatistics() = default; /** * Returns the arithmetic mean of all data recorded. If no observations have been made, returns NaN. * * @return The arithmetic mean of all data recorded, or NaN if the sample count is 0. - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC double Average() const RCPPUTILS_TSA_REQUIRES(mutex_); /** * Returns the maximum value recorded. If size of list is zero, returns NaN. * * @return The maximum value recorded, or NaN if size of data is zero. - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC double Max() const RCPPUTILS_TSA_REQUIRES(mutex_); /** * Returns the minimum value recorded. If size of list is zero, returns NaN. * * @return The minimum value recorded, or NaN if size of data is zero. - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC double Min() const RCPPUTILS_TSA_REQUIRES(mutex_); /** @@ -78,7 +86,8 @@ class MovingAverageStatistics * see https://en.wikipedia.org/wiki/Algorithms_for_calculating_variance#Welford%27s_online_algorithm * * @return The standard deviation (population) of all data recorded, or NaN if size of data is zero. - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC double StandardDeviation() const RCPPUTILS_TSA_REQUIRES(mutex_); /** @@ -88,12 +97,14 @@ class MovingAverageStatistics * * @return StatisticData object, containing average, minimum, maximum, standard deviation (population), * and sample count. - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC StatisticData GetStatistics() const; /** * Reset all calculated values. Equivalent to a new window for a moving average. - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC void Reset(); /** @@ -101,7 +112,8 @@ class MovingAverageStatistics * Note: any input values of NaN will be discarded and not added as a measurement. * * @param item The item that was observed - **/ + */ + LIBSTATISTICS_COLLECTOR_PUBLIC virtual void AddMeasurement(const double item); /** @@ -109,6 +121,7 @@ class MovingAverageStatistics * * @return the number of samples observed */ + LIBSTATISTICS_COLLECTOR_PUBLIC uint64_t GetCount() const; private: diff --git a/include/libstatistics_collector/moving_average_statistics/types.hpp b/include/libstatistics_collector/moving_average_statistics/types.hpp index dd09ed2..bae0b97 100644 --- a/include/libstatistics_collector/moving_average_statistics/types.hpp +++ b/include/libstatistics_collector/moving_average_statistics/types.hpp @@ -19,6 +19,8 @@ #include #include +#include "libstatistics_collector/visibility_control.hpp" + namespace libstatistics_collector { namespace moving_average_statistics @@ -27,7 +29,7 @@ namespace moving_average_statistics /** * A container for statistics data results for a set of recorded observations. */ -struct StatisticData +struct LIBSTATISTICS_COLLECTOR_PUBLIC StatisticData { double average = std::nan(""); double min = std::nan(""); @@ -43,6 +45,7 @@ struct StatisticData * @return std::string formatted struct contents in an easily readable format, e.g., * /"avg=1, min=2, max=3, std_dev=4, count=5/" */ +LIBSTATISTICS_COLLECTOR_PUBLIC std::string StatisticsDataToString(const StatisticData & results); } // namespace moving_average_statistics diff --git a/include/libstatistics_collector/topic_statistics_collector/received_message_age.hpp b/include/libstatistics_collector/topic_statistics_collector/received_message_age.hpp index 6c6e43d..1d7441f 100644 --- a/include/libstatistics_collector/topic_statistics_collector/received_message_age.hpp +++ b/include/libstatistics_collector/topic_statistics_collector/received_message_age.hpp @@ -22,6 +22,7 @@ #include #include "constants.hpp" + #include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp" #include "rcl/time.h" @@ -86,10 +87,6 @@ template class ReceivedMessageAgeCollector : public TopicStatisticsCollector { public: - /** - * Construct a ReceivedMessageAgeCollector object. - * - */ ReceivedMessageAgeCollector() = default; virtual ~ReceivedMessageAgeCollector() = default; @@ -126,6 +123,7 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector { return topic_statistics_constants::kMsgAgeStatName; } + /** * Return messge age metric unit * diff --git a/include/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp b/include/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp index c314a5f..83afc57 100644 --- a/include/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp +++ b/include/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp @@ -38,6 +38,7 @@ class TopicStatisticsCollector : public collector::Collector { public: TopicStatisticsCollector() = default; + virtual ~TopicStatisticsCollector() = default; /** diff --git a/include/libstatistics_collector/visibility_control.hpp b/include/libstatistics_collector/visibility_control.hpp new file mode 100644 index 0000000..5f9b7cf --- /dev/null +++ b/include/libstatistics_collector/visibility_control.hpp @@ -0,0 +1,46 @@ +// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_ +#define LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_ + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define LIBSTATISTICS_COLLECTOR_EXPORT __attribute__ ((dllexport)) + #define LIBSTATISTICS_COLLECTOR_IMPORT __attribute__ ((dllimport)) + #else + #define LIBSTATISTICS_COLLECTOR_EXPORT __declspec(dllexport) + #define LIBSTATISTICS_COLLECTOR_IMPORT __declspec(dllimport) + #endif + #ifdef LIBSTATISTICS_COLLECTOR_BUILDING_LIBRARY + #define LIBSTATISTICS_COLLECTOR_PUBLIC LIBSTATISTICS_COLLECTOR_EXPORT + #else + #define LIBSTATISTICS_COLLECTOR_PUBLIC LIBSTATISTICS_COLLECTOR_IMPORT + #endif + #define LIBSTATISTICS_COLLECTOR_PUBLIC_TYPE LIBSTATISTICS_COLLECTOR_PUBLIC + #define LIBSTATISTICS_COLLECTOR_LOCAL +#else + #define LIBSTATISTICS_COLLECTOR_EXPORT __attribute__ ((visibility("default"))) + #define LIBSTATISTICS_COLLECTOR_IMPORT + #if __GNUC__ >= 4 + #define LIBSTATISTICS_COLLECTOR_PUBLIC __attribute__ ((visibility("default"))) + #define LIBSTATISTICS_COLLECTOR_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define LIBSTATISTICS_COLLECTOR_PUBLIC + #define LIBSTATISTICS_COLLECTOR_LOCAL + #endif + #define LIBSTATISTICS_COLLECTOR_PUBLIC_TYPE +#endif + +#endif // LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_ From 4589c1b5f2eeb2127feeb5cc08e0f56942db66de Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 10:58:37 -0700 Subject: [PATCH 2/7] Add test fixes Signed-off-by: Devin Bonnie --- test/collector/test_collector.cpp | 1 - .../test_moving_average_statistics.cpp | 6 ++---- .../test_received_message_age.cpp | 6 ++++-- 3 files changed, 6 insertions(+), 7 deletions(-) diff --git a/test/collector/test_collector.cpp b/test/collector/test_collector.cpp index e2a02f1..f321223 100644 --- a/test/collector/test_collector.cpp +++ b/test/collector/test_collector.cpp @@ -22,7 +22,6 @@ #include "libstatistics_collector/collector/collector.hpp" - namespace { constexpr const char kTestMetricName[] = "test_metric_name"; diff --git a/test/moving_average_statistics/test_moving_average_statistics.cpp b/test/moving_average_statistics/test_moving_average_statistics.cpp index 266279d..a327ff2 100644 --- a/test/moving_average_statistics/test_moving_average_statistics.cpp +++ b/test/moving_average_statistics/test_moving_average_statistics.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include #include @@ -36,7 +35,6 @@ const std::array kTestData{-3.5, -2.1, -1.1, 0.0, 4.7, 5. 6.7, 9.9, 11.0}; } // namespace - /** * Test fixture */ @@ -122,7 +120,7 @@ TEST_F(MovingAverageStatisticsTestFixture, TestGetStatistics) { EXPECT_DOUBLE_EQ(result.min, kExpectedMin); EXPECT_DOUBLE_EQ(result.max, kExpectedMax); EXPECT_DOUBLE_EQ(result.standard_deviation, kExpectedStd); - EXPECT_DOUBLE_EQ(result.sample_count, kExpectedSize); + EXPECT_EQ(result.sample_count, kExpectedSize); } TEST_F(MovingAverageStatisticsTestFixture, TestGetStatisticsInt) { @@ -145,7 +143,7 @@ TEST_F(MovingAverageStatisticsTestFixture, TestGetStatisticsInt) { EXPECT_DOUBLE_EQ(result.min, kExpectedMinimum); EXPECT_DOUBLE_EQ(result.max, kExpectedMaximum); EXPECT_DOUBLE_EQ(result.standard_deviation, kExpectedStd); - EXPECT_DOUBLE_EQ(result.sample_count, kExpectedSize); + EXPECT_EQ(result.sample_count, kExpectedSize); } TEST_F(MovingAverageStatisticsTestFixture, TestReset) { diff --git a/test/topic_statistics_collector/test_received_message_age.cpp b/test/topic_statistics_collector/test_received_message_age.cpp index 0ab4e82..b414e25 100644 --- a/test/topic_statistics_collector/test_received_message_age.cpp +++ b/test/topic_statistics_collector/test_received_message_age.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include #include @@ -97,8 +96,11 @@ TEST(ReceivedMessageAgeTest, TestAgeMeasurement) { EXPECT_TRUE(test_collector.IsStarted()) << "Expect to be started"; rcl_time_point_value_t fake_now_nanos_{kStartTime}; + auto msg = DummyMessage{}; - msg.header.stamp.nanosec = fake_now_nanos_; + msg.header.stamp.sec = static_cast(RCL_NS_TO_S(fake_now_nanos_)); + msg.header.stamp.nanosec = static_cast(fake_now_nanos_ % (1000 * 1000 * 1000)); + fake_now_nanos_ += std::chrono::duration_cast(kDefaultDurationSeconds).count(); From 61df005bb66dc6c40d1357a9e0f2ec58b224e850 Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 11:00:09 -0700 Subject: [PATCH 3/7] Add ament_cmake_ros dependency Signed-off-by: Devin Bonnie --- package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/package.xml b/package.xml index 2bd08c9..83e2129 100644 --- a/package.xml +++ b/package.xml @@ -8,6 +8,7 @@ Apache License 2.0 ament_cmake + ament_cmake_ros rcl rcpputils From 77ee909e4fff0a07115bd2008f65d8605e04f74e Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 11:14:55 -0700 Subject: [PATCH 4/7] Alphasort CmakeLists.txt Signed-off-by: Devin Bonnie --- CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index eb5c140..e3e1260 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,10 +29,10 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(ament_cmake_ros REQUIRED) -find_package(statistics_msgs REQUIRED) find_package(rcl REQUIRED) find_package(rcpputils REQUIRED) find_package(rosidl_default_generators REQUIRED) +find_package(statistics_msgs REQUIRED) find_package(std_msgs REQUIRED) include_directories("include") @@ -47,9 +47,9 @@ add_library(${PROJECT_NAME} target_compile_definitions(${PROJECT_NAME} PRIVATE "LIBSTATISTICS_COLLECTOR_BUILDING_LIBRARY") ament_target_dependencies(${PROJECT_NAME} - "statistics_msgs" "rcl" - "rcpputils") + "rcpputils" + "statistics_msgs") install( TARGETS ${PROJECT_NAME} @@ -60,7 +60,7 @@ install( ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}) -ament_export_dependencies("statistics_msgs" "rcl" "rcpputils" "rosidl_default_runtime") +ament_export_dependencies("rcl" "rcpputils" "rosidl_default_runtime" statistics_msgs) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) From eba0a11ee6be05078f3883fb83fc1749e28d17e5 Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 11:15:32 -0700 Subject: [PATCH 5/7] Alphasort package.xml Signed-off-by: Devin Bonnie --- package.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/package.xml b/package.xml index 83e2129..d8a655d 100644 --- a/package.xml +++ b/package.xml @@ -10,13 +10,13 @@ ament_cmake ament_cmake_ros + rosidl_default_generators + std_msgs + rcl rcpputils statistics_msgs - rosidl_default_generators - std_msgs - rosidl_default_runtime std_msgs From 47efcc337dd0630189c47dd3a27b484ad2f6f4ec Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 11:19:30 -0700 Subject: [PATCH 6/7] Alphasort collector.hpp Signed-off-by: Devin Bonnie --- include/libstatistics_collector/collector/collector.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/libstatistics_collector/collector/collector.hpp b/include/libstatistics_collector/collector/collector.hpp index d4813b1..88b957a 100644 --- a/include/libstatistics_collector/collector/collector.hpp +++ b/include/libstatistics_collector/collector/collector.hpp @@ -18,12 +18,12 @@ #include #include -#include "metric_details_interface.hpp" - #include "libstatistics_collector/visibility_control.hpp" #include "libstatistics_collector/moving_average_statistics/moving_average.hpp" #include "libstatistics_collector/moving_average_statistics/types.hpp" +#include "metric_details_interface.hpp" + #include "rcpputils/thread_safety_annotations.hpp" namespace libstatistics_collector From b2e0cd3439af3fa0e89484eb1e2527bd51d31487 Mon Sep 17 00:00:00 2001 From: Devin Bonnie Date: Fri, 17 Apr 2020 11:22:45 -0700 Subject: [PATCH 7/7] Add quotes in cmake Signed-off-by: Devin Bonnie --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e3e1260..131f9a0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -60,7 +60,7 @@ install( ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}) -ament_export_dependencies("rcl" "rcpputils" "rosidl_default_runtime" statistics_msgs) +ament_export_dependencies("rcl" "rcpputils" "rosidl_default_runtime" "statistics_msgs") if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED)