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

Commit 43cd499

Browse files
authored
Fix Windows build (#136)
Signed-off-by: Emerson Knapp <emerson.b.knapp@gmail.com>
1 parent fda0f37 commit 43cd499

File tree

10 files changed

+18
-62
lines changed

10 files changed

+18
-62
lines changed

libstatistics_collector/CMakeLists.txt

+2-3
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,6 @@ ament_target_dependencies(${PROJECT_NAME}
5353

5454
install(
5555
TARGETS ${PROJECT_NAME}
56-
EXPORT "${PROJECT_NAME}-targets"
5756
ARCHIVE DESTINATION lib
5857
LIBRARY DESTINATION lib
5958
RUNTIME DESTINATION bin
@@ -99,8 +98,8 @@ if(BUILD_TESTING)
9998
endif()
10099

101100
install(
102-
DIRECTORY include/ ${CMAKE_CURRENT_BINARY_DIR}/include/
101+
DIRECTORY include/
103102
DESTINATION include
104103
)
105104

106-
ament_package()
105+
ament_package()

libstatistics_collector/include/libstatistics_collector/collector/collector.hpp

+1-12
Original file line numberDiff line numberDiff line change
@@ -34,13 +34,11 @@ namespace collector
3434
/**
3535
* Simple class in order to collect observed data and generate statistics for the given observations.
3636
*/
37-
class Collector : public MetricDetailsInterface
37+
class LIBSTATISTICS_COLLECTOR_PUBLIC Collector : public MetricDetailsInterface
3838
{
3939
public:
40-
LIBSTATISTICS_COLLECTOR_PUBLIC
4140
Collector() = default;
4241

43-
LIBSTATISTICS_COLLECTOR_PUBLIC
4442
virtual ~Collector() = default;
4543

4644
/**
@@ -49,37 +47,32 @@ class Collector : public MetricDetailsInterface
4947
*
5048
* @param the measurement observed
5149
*/
52-
LIBSTATISTICS_COLLECTOR_PUBLIC
5350
virtual void AcceptData(const double measurement);
5451

5552
/**
5653
* Return the statistics for all of the observed data.
5754
*
5855
* @return the StatisticData for all the observed measurements
5956
*/
60-
LIBSTATISTICS_COLLECTOR_PUBLIC
6157
virtual moving_average_statistics::StatisticData GetStatisticsResults() const;
6258

6359
/**
6460
* Clear / reset all current measurements.
6561
*/
66-
LIBSTATISTICS_COLLECTOR_PUBLIC
6762
virtual void ClearCurrentMeasurements();
6863

6964
/**
7065
* Return true is start has been called, false otherwise.
7166
*
7267
* @return the started state of this collector
7368
*/
74-
LIBSTATISTICS_COLLECTOR_PUBLIC
7569
bool IsStarted() const;
7670

7771
/**
7872
* Return a pretty printed status representation of this class
7973
*
8074
* @return a string detailing the current status
8175
*/
82-
LIBSTATISTICS_COLLECTOR_PUBLIC
8376
virtual std::string GetStatusString() const;
8477

8578
// TODO(dabonnie): uptime (once start has been called)
@@ -91,7 +84,6 @@ class Collector : public MetricDetailsInterface
9184
*
9285
* @return true if started, false if an error occurred
9386
*/
94-
LIBSTATISTICS_COLLECTOR_PUBLIC
9587
virtual bool Start();
9688

9789
/**
@@ -103,7 +95,6 @@ class Collector : public MetricDetailsInterface
10395
*
10496
* @return true if stopped, false if an error occurred
10597
*/
106-
LIBSTATISTICS_COLLECTOR_PUBLIC
10798
virtual bool Stop();
10899

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

118108
/**
119109
* Override in order to perform necessary teardown.
120110
*
121111
* @return true if teardown was successful, false otherwise.
122112
*/
123-
LIBSTATISTICS_COLLECTOR_PUBLIC
124113
virtual bool SetupStop() = 0 RCPPUTILS_TSA_REQUIRES(mutex_);
125114

126115
mutable std::mutex mutex_;

libstatistics_collector/include/libstatistics_collector/moving_average_statistics/moving_average.hpp

+1-11
Original file line numberDiff line numberDiff line change
@@ -46,37 +46,32 @@ namespace moving_average_statistics
4646
*
4747
* When statistics are not available, e.g. no observations have been made, NaNs are returned.
4848
*/
49-
class MovingAverageStatistics
49+
class LIBSTATISTICS_COLLECTOR_PUBLIC MovingAverageStatistics
5050
{
5151
public:
52-
LIBSTATISTICS_COLLECTOR_PUBLIC
5352
MovingAverageStatistics() = default;
5453

55-
LIBSTATISTICS_COLLECTOR_PUBLIC
5654
~MovingAverageStatistics() = default;
5755

5856
/**
5957
* Returns the arithmetic mean of all data recorded. If no observations have been made, returns NaN.
6058
*
6159
* @return The arithmetic mean of all data recorded, or NaN if the sample count is 0.
6260
*/
63-
LIBSTATISTICS_COLLECTOR_PUBLIC
6461
double Average() const RCPPUTILS_TSA_REQUIRES(mutex_);
6562

6663
/**
6764
* Returns the maximum value recorded. If size of list is zero, returns NaN.
6865
*
6966
* @return The maximum value recorded, or NaN if size of data is zero.
7067
*/
71-
LIBSTATISTICS_COLLECTOR_PUBLIC
7268
double Max() const RCPPUTILS_TSA_REQUIRES(mutex_);
7369

7470
/**
7571
* Returns the minimum value recorded. If size of list is zero, returns NaN.
7672
*
7773
* @return The minimum value recorded, or NaN if size of data is zero.
7874
*/
79-
LIBSTATISTICS_COLLECTOR_PUBLIC
8075
double Min() const RCPPUTILS_TSA_REQUIRES(mutex_);
8176

8277
/**
@@ -87,7 +82,6 @@ class MovingAverageStatistics
8782
*
8883
* @return The standard deviation (population) of all data recorded, or NaN if size of data is zero.
8984
*/
90-
LIBSTATISTICS_COLLECTOR_PUBLIC
9185
double StandardDeviation() const RCPPUTILS_TSA_REQUIRES(mutex_);
9286

9387
/**
@@ -98,13 +92,11 @@ class MovingAverageStatistics
9892
* @return StatisticData object, containing average, minimum, maximum, standard deviation (population),
9993
* and sample count.
10094
*/
101-
LIBSTATISTICS_COLLECTOR_PUBLIC
10295
StatisticData GetStatistics() const;
10396

10497
/**
10598
* Reset all calculated values. Equivalent to a new window for a moving average.
10699
*/
107-
LIBSTATISTICS_COLLECTOR_PUBLIC
108100
void Reset();
109101

110102
/**
@@ -113,15 +105,13 @@ class MovingAverageStatistics
113105
*
114106
* @param item The item that was observed
115107
*/
116-
LIBSTATISTICS_COLLECTOR_PUBLIC
117108
virtual void AddMeasurement(const double item);
118109

119110
/**
120111
* Return the number of samples observed
121112
*
122113
* @return the number of samples observed
123114
*/
124-
LIBSTATISTICS_COLLECTOR_PUBLIC
125115
uint64_t GetCount() const;
126116

127117
private:

libstatistics_collector/include/libstatistics_collector/moving_average_statistics/types.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ namespace moving_average_statistics
2929
/**
3030
* A container for statistics data results for a set of recorded observations.
3131
*/
32-
struct StatisticData
32+
struct LIBSTATISTICS_COLLECTOR_PUBLIC StatisticData
3333
{
3434
double average = std::nan("");
3535
double min = std::nan("");

libstatistics_collector/include/libstatistics_collector/topic_statistics_collector/received_message_age.hpp

+1-10
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,6 @@ struct HasHeader<M, decltype((void) M::header)>: std::true_type {};
5757
template<typename M, typename Enable = void>
5858
struct TimeStamp
5959
{
60-
LIBSTATISTICS_COLLECTOR_PUBLIC
6160
static std::pair<bool, int64_t> value(const M &)
6261
{
6362
return std::make_pair(false, 0);
@@ -72,7 +71,6 @@ struct TimeStamp
7271
template<typename M>
7372
struct TimeStamp<M, typename std::enable_if<HasHeader<M>::value>::type>
7473
{
75-
LIBSTATISTICS_COLLECTOR_PUBLIC
7674
static std::pair<bool, int64_t> value(const M & m)
7775
{
7876
const auto stamp = m.header.stamp;
@@ -90,10 +88,8 @@ template<typename T>
9088
class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
9189
{
9290
public:
93-
LIBSTATISTICS_COLLECTOR_PUBLIC
9491
ReceivedMessageAgeCollector() = default;
9592

96-
LIBSTATISTICS_COLLECTOR_PUBLIC
9793
virtual ~ReceivedMessageAgeCollector() = default;
9894

9995
/**
@@ -102,7 +98,6 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
10298
* @param received_message, the message to calculate age of.
10399
* @param time the message was received in nanoseconds
104100
*/
105-
LIBSTATISTICS_COLLECTOR_PUBLIC
106101
void OnMessageReceived(
107102
const T & received_message,
108103
const rcl_time_point_value_t now_nanoseconds) override
@@ -125,7 +120,6 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
125120
*
126121
* @return a string representing message age metric name
127122
*/
128-
LIBSTATISTICS_COLLECTOR_PUBLIC
129123
std::string GetMetricName() const override
130124
{
131125
return topic_statistics_constants::kMsgAgeStatName;
@@ -136,20 +130,17 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
136130
*
137131
* @return a string representing messager age metric unit
138132
*/
139-
LIBSTATISTICS_COLLECTOR_PUBLIC
140133
std::string GetMetricUnit() const override
141134
{
142135
return topic_statistics_constants::kMillisecondUnitName;
143136
}
144137

145138
protected:
146-
147-
LIBSTATISTICS_COLLECTOR_PUBLIC
148139
bool SetupStart() override
149140
{
150141
return true;
151142
}
152-
LIBSTATISTICS_COLLECTOR_PUBLIC
143+
153144
bool SetupStop() override
154145
{
155146
return true;

libstatistics_collector/include/libstatistics_collector/topic_statistics_collector/received_message_period.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -47,13 +47,11 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
4747
* Construct a ReceivedMessagePeriodCollector object.
4848
*
4949
*/
50-
LIBSTATISTICS_COLLECTOR_PUBLIC
5150
ReceivedMessagePeriodCollector()
5251
{
5352
ResetTimeLastMessageReceived();
5453
}
5554

56-
LIBSTATISTICS_COLLECTOR_PUBLIC
5755
virtual ~ReceivedMessagePeriodCollector() = default;
5856

5957
/**
@@ -63,7 +61,6 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
6361
* @param received_message
6462
* @param time the message was received in nanoseconds
6563
*/
66-
LIBSTATISTICS_COLLECTOR_PUBLIC
6764
void OnMessageReceived(const T & received_message, const rcl_time_point_value_t now_nanoseconds)
6865
override RCPPUTILS_TSA_REQUIRES(mutex_)
6966
{
@@ -86,7 +83,6 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
8683
*
8784
* @return a string representing message period metric name
8885
*/
89-
LIBSTATISTICS_COLLECTOR_PUBLIC
9086
std::string GetMetricName() const override
9187
{
9288
return topic_statistics_constants::kMsgPeriodStatName;
@@ -97,7 +93,6 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
9793
*
9894
* @return a string representing message period metric unit
9995
*/
100-
LIBSTATISTICS_COLLECTOR_PUBLIC
10196
std::string GetMetricUnit() const override
10297
{
10398
return topic_statistics_constants::kMillisecondUnitName;
@@ -108,14 +103,12 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
108103
* Reset the time_last_message_received_ member.
109104
* @return true
110105
*/
111-
LIBSTATISTICS_COLLECTOR_PUBLIC
112106
bool SetupStart() override
113107
{
114108
ResetTimeLastMessageReceived();
115109
return true;
116110
}
117111

118-
LIBSTATISTICS_COLLECTOR_PUBLIC
119112
bool SetupStop() override
120113
{
121114
return true;

libstatistics_collector/include/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -38,10 +38,8 @@ template<typename T>
3838
class TopicStatisticsCollector : public collector::Collector
3939
{
4040
public:
41-
LIBSTATISTICS_COLLECTOR_PUBLIC
4241
TopicStatisticsCollector() = default;
4342

44-
LIBSTATISTICS_COLLECTOR_PUBLIC
4543
virtual ~TopicStatisticsCollector() = default;
4644

4745
/**
@@ -52,7 +50,6 @@ class TopicStatisticsCollector : public collector::Collector
5250
* following 1). the time provided is strictly monotonic 2). the time provided uses the same source
5351
* as time obtained from the message header.
5452
*/
55-
LIBSTATISTICS_COLLECTOR_PUBLIC
5653
virtual void OnMessageReceived(
5754
const T & received_message,
5855
const rcl_time_point_value_t now_nanoseconds) = 0;

libstatistics_collector/include/libstatistics_collector/visibility_control.hpp

+11-14
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,8 @@
1515
#ifndef LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_
1616
#define LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_
1717

18-
// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
19-
// https://gcc.gnu.org/wiki/Visibility
20-
2118
#if defined _WIN32 || defined __CYGWIN__
22-
#ifdef __GNUC__
19+
#ifdef __GNUC__
2320
#define LIBSTATISTICS_COLLECTOR_EXPORT __attribute__ ((dllexport))
2421
#define LIBSTATISTICS_COLLECTOR_IMPORT __attribute__ ((dllimport))
2522
#else
@@ -34,16 +31,16 @@
3431
#define LIBSTATISTICS_COLLECTOR_PUBLIC_TYPE LIBSTATISTICS_COLLECTOR_PUBLIC
3532
#define LIBSTATISTICS_COLLECTOR_LOCAL
3633
#else
37-
#define LIBSTATISTICS_COLLECTOR_EXPORT __attribute__ ((visibility("default")))
38-
#define LIBSTATISTICS_COLLECTOR_IMPORT
39-
#if __GNUC__ >= 4
40-
#define LIBSTATISTICS_COLLECTOR_PUBLIC __attribute__ ((visibility("default")))
41-
#define LIBSTATISTICS_COLLECTOR_LOCAL __attribute__ ((visibility("hidden")))
42-
#else
43-
#define LIBSTATISTICS_COLLECTOR_PUBLIC
44-
#define LIBSTATISTICS_COLLECTOR_LOCAL
45-
#endif
46-
#define LIBSTATISTICS_COLLECTOR_PUBLIC_TYPE
34+
#define LIBSTATISTICS_COLLECTOR_EXPORT __attribute__ ((visibility("default")))
35+
#define LIBSTATISTICS_COLLECTOR_IMPORT
36+
#if __GNUC__ >= 4
37+
#define LIBSTATISTICS_COLLECTOR_PUBLIC __attribute__ ((visibility("default")))
38+
#define LIBSTATISTICS_COLLECTOR_LOCAL __attribute__ ((visibility("hidden")))
39+
#else
40+
#define LIBSTATISTICS_COLLECTOR_PUBLIC
41+
#define LIBSTATISTICS_COLLECTOR_LOCAL
42+
#endif
43+
#define LIBSTATISTICS_COLLECTOR_PUBLIC_TYPE
4744
#endif
4845

4946
#endif // LIBSTATISTICS_COLLECTOR__VISIBILITY_CONTROL_HPP_

libstatistics_collector/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<license>Apache License 2.0</license>
99

1010
<buildtool_depend>ament_cmake</buildtool_depend>
11+
<buildtool_depend>ament_cmake_ros</buildtool_depend>
1112

1213
<depend>metrics_statistics_msgs</depend>
1314
<depend>rcl</depend>

libstatistics_collector/test/moving_average_statistics/test_moving_average_statistics.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#include <thread>
2121

2222
#include "libstatistics_collector/moving_average_statistics/moving_average.hpp"
23-
#include "libstatistics_collector/visibility_control.hpp"
2423

2524
namespace
2625
{

0 commit comments

Comments
 (0)