Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Apply windows vibility fix changes #5

Merged
merged 7 commits into from
Apr 17, 2020
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 24 additions & 21 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}})
Expand All @@ -28,30 +28,40 @@ endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_ros 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}
"rcl"
"rcpputils"
"statistics_msgs")

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("rcl" "rcpputils" "rosidl_default_runtime" statistics_msgs)
dabonnie marked this conversation as resolved.
Show resolved Hide resolved

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gtest REQUIRED)
Expand All @@ -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()
14 changes: 13 additions & 1 deletion include/libstatistics_collector/collector/collector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,11 @@
#include <mutex>
#include <string>

#include "metric_details_interface.hpp"

#include "libstatistics_collector/visibility_control.hpp"
dabonnie marked this conversation as resolved.
Show resolved Hide resolved
#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"

Expand All @@ -35,7 +37,10 @@ namespace collector
class Collector : public MetricDetailsInterface
{
public:
LIBSTATISTICS_COLLECTOR_PUBLIC
Collector() = default;

LIBSTATISTICS_COLLECTOR_PUBLIC
virtual ~Collector() = default;

/**
Expand All @@ -44,32 +49,37 @@ class Collector : public MetricDetailsInterface
*
* @param the measurement observed
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual void AcceptData(const double measurement);

/**
* Return the statistics for all of the observed data.
*
* @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();

/**
* Return true is start has been called, false otherwise.
*
* @return the started state of this collector
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
bool IsStarted() const;

/**
* Return a pretty printed status representation of this class
*
* @return a string detailing the current status
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual std::string GetStatusString() const;

// TODO(dabonnie): uptime (once start has been called)
Expand All @@ -81,6 +91,7 @@ class Collector : public MetricDetailsInterface
*
* @return true if started, false if an error occurred
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual bool Start();

/**
Expand All @@ -92,6 +103,7 @@ class Collector : public MetricDetailsInterface
*
* @return true if stopped, false if an error occurred
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual bool Stop();

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <string>

#include "libstatistics_collector/visibility_control.hpp"

namespace libstatistics_collector
{
namespace collector
Expand All @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@

#include "types.hpp"

#include "libstatistics_collector/visibility_control.hpp"

#include "rcpputils/thread_safety_annotations.hpp"

namespace libstatistics_collector
Expand All @@ -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_);

/**
Expand All @@ -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_);

/**
Expand All @@ -88,27 +97,31 @@ 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();

/**
* Observe a sample for the given window. The input item is used to calculate statistics.
* 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);

/**
* Return the number of samples observed
*
* @return the number of samples observed
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
uint64_t GetCount() const;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <sstream>
#include <string>

#include "libstatistics_collector/visibility_control.hpp"

namespace libstatistics_collector
{
namespace moving_average_statistics
Expand All @@ -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("");
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <utility>

#include "constants.hpp"

#include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp"

#include "rcl/time.h"
Expand Down Expand Up @@ -86,10 +87,6 @@ template<typename T>
class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
{
public:
/**
* Construct a ReceivedMessageAgeCollector object.
*
*/
ReceivedMessageAgeCollector() = default;

virtual ~ReceivedMessageAgeCollector() = default;
Expand Down Expand Up @@ -126,6 +123,7 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
{
return topic_statistics_constants::kMsgAgeStatName;
}

/**
* Return messge age metric unit
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ class TopicStatisticsCollector : public collector::Collector
{
public:
TopicStatisticsCollector() = default;

virtual ~TopicStatisticsCollector() = default;

/**
Expand Down
Loading