Skip to content
This repository was archived by the owner on Jun 10, 2021. It is now read-only.

Fix windows build #136

Merged
merged 1 commit into from
Apr 16, 2020
Merged
Show file tree
Hide file tree
Changes from all 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
5 changes: 2 additions & 3 deletions libstatistics_collector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ ament_target_dependencies(${PROJECT_NAME}

install(
TARGETS ${PROJECT_NAME}
EXPORT "${PROJECT_NAME}-targets"
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand Down Expand Up @@ -99,8 +98,8 @@ if(BUILD_TESTING)
endif()

install(
DIRECTORY include/ ${CMAKE_CURRENT_BINARY_DIR}/include/
DIRECTORY include/
DESTINATION include
)

ament_package()
ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,11 @@ namespace collector
/**
* Simple class in order to collect observed data and generate statistics for the given observations.
*/
class Collector : public MetricDetailsInterface
class LIBSTATISTICS_COLLECTOR_PUBLIC Collector : public MetricDetailsInterface
{
public:
LIBSTATISTICS_COLLECTOR_PUBLIC
Collector() = default;

LIBSTATISTICS_COLLECTOR_PUBLIC
virtual ~Collector() = default;

/**
Expand All @@ -49,37 +47,32 @@ 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 @@ -91,7 +84,6 @@ class Collector : public MetricDetailsInterface
*
* @return true if started, false if an error occurred
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual bool Start();

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

private:
Expand All @@ -112,15 +103,13 @@ class Collector : public MetricDetailsInterface
*
* @return true if setup was successful, false otherwise.
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual bool SetupStart() = 0 RCPPUTILS_TSA_REQUIRES(mutex_);

/**
* Override in order to perform necessary teardown.
*
* @return true if teardown was successful, false otherwise.
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual bool SetupStop() = 0 RCPPUTILS_TSA_REQUIRES(mutex_);

mutable std::mutex mutex_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,37 +46,32 @@ namespace moving_average_statistics
*
* When statistics are not available, e.g. no observations have been made, NaNs are returned.
*/
class MovingAverageStatistics
class LIBSTATISTICS_COLLECTOR_PUBLIC 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 @@ -87,7 +82,6 @@ class MovingAverageStatistics
*
* @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 @@ -98,13 +92,11 @@ 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();

/**
Expand All @@ -113,15 +105,13 @@ class MovingAverageStatistics
*
* @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 @@ -29,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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,6 @@ struct HasHeader<M, decltype((void) M::header)>: std::true_type {};
template<typename M, typename Enable = void>
struct TimeStamp
{
LIBSTATISTICS_COLLECTOR_PUBLIC
static std::pair<bool, int64_t> value(const M &)
{
return std::make_pair(false, 0);
Expand All @@ -72,7 +71,6 @@ struct TimeStamp
template<typename M>
struct TimeStamp<M, typename std::enable_if<HasHeader<M>::value>::type>
{
LIBSTATISTICS_COLLECTOR_PUBLIC
static std::pair<bool, int64_t> value(const M & m)
{
const auto stamp = m.header.stamp;
Expand All @@ -90,10 +88,8 @@ template<typename T>
class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
{
public:
LIBSTATISTICS_COLLECTOR_PUBLIC
ReceivedMessageAgeCollector() = default;

LIBSTATISTICS_COLLECTOR_PUBLIC
virtual ~ReceivedMessageAgeCollector() = default;

/**
Expand All @@ -102,7 +98,6 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
* @param received_message, the message to calculate age of.
* @param time the message was received in nanoseconds
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
void OnMessageReceived(
const T & received_message,
const rcl_time_point_value_t now_nanoseconds) override
Expand All @@ -125,7 +120,6 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
*
* @return a string representing message age metric name
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
std::string GetMetricName() const override
{
return topic_statistics_constants::kMsgAgeStatName;
Expand All @@ -136,20 +130,17 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
*
* @return a string representing messager age metric unit
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
std::string GetMetricUnit() const override
{
return topic_statistics_constants::kMillisecondUnitName;
}

protected:

LIBSTATISTICS_COLLECTOR_PUBLIC
bool SetupStart() override
{
return true;
}
LIBSTATISTICS_COLLECTOR_PUBLIC

bool SetupStop() override
{
return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,13 +47,11 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
* Construct a ReceivedMessagePeriodCollector object.
*
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
ReceivedMessagePeriodCollector()
{
ResetTimeLastMessageReceived();
}

LIBSTATISTICS_COLLECTOR_PUBLIC
virtual ~ReceivedMessagePeriodCollector() = default;

/**
Expand All @@ -63,7 +61,6 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
* @param received_message
* @param time the message was received in nanoseconds
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
void OnMessageReceived(const T & received_message, const rcl_time_point_value_t now_nanoseconds)
override RCPPUTILS_TSA_REQUIRES(mutex_)
{
Expand All @@ -86,7 +83,6 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
*
* @return a string representing message period metric name
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
std::string GetMetricName() const override
{
return topic_statistics_constants::kMsgPeriodStatName;
Expand All @@ -97,7 +93,6 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
*
* @return a string representing message period metric unit
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
std::string GetMetricUnit() const override
{
return topic_statistics_constants::kMillisecondUnitName;
Expand All @@ -108,14 +103,12 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
* Reset the time_last_message_received_ member.
* @return true
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
bool SetupStart() override
{
ResetTimeLastMessageReceived();
return true;
}

LIBSTATISTICS_COLLECTOR_PUBLIC
bool SetupStop() override
{
return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,8 @@ template<typename T>
class TopicStatisticsCollector : public collector::Collector
{
public:
LIBSTATISTICS_COLLECTOR_PUBLIC
TopicStatisticsCollector() = default;

LIBSTATISTICS_COLLECTOR_PUBLIC
virtual ~TopicStatisticsCollector() = default;

/**
Expand All @@ -52,7 +50,6 @@ class TopicStatisticsCollector : public collector::Collector
* following 1). the time provided is strictly monotonic 2). the time provided uses the same source
* as time obtained from the message header.
*/
LIBSTATISTICS_COLLECTOR_PUBLIC
virtual void OnMessageReceived(
const T & received_message,
const rcl_time_point_value_t now_nanoseconds) = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,8 @@
#ifndef LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_
#define LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_

// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility

#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#ifdef __GNUC__
#define LIBSTATISTICS_COLLECTOR_EXPORT __attribute__ ((dllexport))
#define LIBSTATISTICS_COLLECTOR_IMPORT __attribute__ ((dllimport))
#else
Expand All @@ -34,16 +31,16 @@
#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
#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_
1 change: 1 addition & 0 deletions libstatistics_collector/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_ros</buildtool_depend>

<depend>metrics_statistics_msgs</depend>
<depend>rcl</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <thread>

#include "libstatistics_collector/moving_average_statistics/moving_average.hpp"
#include "libstatistics_collector/visibility_control.hpp"

namespace
{
Expand Down