Skip to content

Commit 76b8e96

Browse files
authored
Merge pull request #42 from ethz-asl/fix/melodic
changed logging to compile on melodic
2 parents 8ca1ebf + 51419fb commit 76b8e96

File tree

4 files changed

+28
-8
lines changed

4 files changed

+28
-8
lines changed

cuckoo_time_translator_algorithms/include/cuckoo_time_translator/AbstractAssert.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
#ifndef H7E81A0F8_04E4_435D_8F39_103889A163E8
22
#define H7E81A0F8_04E4_435D_8F39_103889A163E8
33

4-
#include <console_bridge/console.h>
4+
#include "Logging.h"
55

66
#define AASSERT(x, message) \
77
do { \
88
if (!(x)) { \
9-
logError("ASSERTION %s FAILED: %s (%s:%d)", #x, message, __FILE__, __LINE__); \
9+
CUCKOO_TIME_TRANSLATOR_logError("ASSERTION %s FAILED: %s (%s:%d)", #x, message, __FILE__, __LINE__); \
1010
throw std::runtime_error(message); \
1111
} \
1212
} while (0)
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
#ifndef HCEF9D5FC_9095_462B_B900_048DD967629F
2+
#define HCEF9D5FC_9095_462B_B900_048DD967629F
3+
4+
#include <console_bridge/console.h>
5+
6+
#ifdef logError
7+
8+
#define CUCKOO_TIME_TRANSLATOR_logError(fmt, ...) logError(fmt, ##__VA_ARGS__)
9+
#define CUCKOO_TIME_TRANSLATOR_logWarn(fmt, ...) logWarn(fmt, ##__VA_ARGS__)
10+
#define CUCKOO_TIME_TRANSLATOR_logInform(fmt, ...) logInform(fmt, ##__VA_ARGS__)
11+
#define CUCKOO_TIME_TRANSLATOR_logDebug(fmt, ...) logDebug(fmt, ##__VA_ARGS__)
12+
13+
#else
14+
15+
#define CUCKOO_TIME_TRANSLATOR_logError(fmt, ...) CONSOLE_BRIDGE_logError(fmt, ##__VA_ARGS__)
16+
#define CUCKOO_TIME_TRANSLATOR_logWarn(fmt, ...) CONSOLE_BRIDGE_logWarn(fmt, ##__VA_ARGS__)
17+
#define CUCKOO_TIME_TRANSLATOR_logInform(fmt, ...) CONSOLE_BRIDGE_logInform(fmt, ##__VA_ARGS__)
18+
#define CUCKOO_TIME_TRANSLATOR_logDebug(fmt, ...) CONSOLE_BRIDGE_logDebug(fmt, ##__VA_ARGS__)
19+
20+
#endif
21+
22+
#endif /* HCEF9D5FC_9095_462B_B900_048DD967629F */

cuckoo_time_translator_algorithms/src/KalmanOwt.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
#include <iostream>
44
#include <stdexcept>
55

6-
#include <console_bridge/console.h>
76
#include <cuckoo_time_translator/AbstractAssert.h>
87

98
namespace cuckoo_time_translator {
@@ -78,7 +77,7 @@ LocalTime KalmanOwt::updateAndTranslateToLocalTimestamp(const RemoteTime remoteT
7877
const double mahalDistance = sqrt(measurementResidual*measurementResidual*(1.0/S));
7978

8079
if(config.outlierThreshold && mahalDistance > config.outlierThreshold){
81-
logWarn("KalmanOwt: local_time=%f, remote_time=%f -> measurement_residual=%g, mahal_distance=%g!", localTimeSecs, remoteTimeTics, measurementResidual, mahalDistance);
80+
CUCKOO_TIME_TRANSLATOR_logWarn("KalmanOwt: local_time=%f, remote_time=%f -> measurement_residual=%g, mahal_distance=%g!", localTimeSecs, remoteTimeTics, measurementResidual, mahalDistance);
8281
} else {
8382
x_ = x_ + K * measurementResidual;
8483
P_ = (Eigen::Matrix2d::Identity() - K * H_) * P_;

cuckoo_time_translator_algorithms/src/TimestampUnwrapper.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
#include <cuckoo_time_translator/TimestampUnwrapper.h>
2-
3-
#include <console_bridge/console.h>
2+
#include <cuckoo_time_translator/Logging.h>
43

54
namespace cuckoo_time_translator {
65

@@ -28,11 +27,11 @@ void WrappingClockParameters::checkNewDeviceStamp(uint64_t wrapsCounter, uint64_
2827
maxStamp_ = std::max(newDeviceStamp, maxStamp_);
2928
if (newDeviceStamp >= wrapAroundNumber_){
3029
const uint64_t newWrapAroundNumber = newDeviceStamp + 1;
31-
logError("newDeviceStamp=%u is larger than wrapAroundNumber=%lu -> adapting wrapAroundNumber to %lu!", newDeviceStamp, wrapAroundNumber_, newWrapAroundNumber);
30+
CUCKOO_TIME_TRANSLATOR_logError("newDeviceStamp=%u is larger than wrapAroundNumber=%lu -> adapting wrapAroundNumber to %lu!", newDeviceStamp, wrapAroundNumber_, newWrapAroundNumber);
3231
wrapAroundNumber_ = newWrapAroundNumber;
3332
}
3433
if(wrapsCounter % 10 == 9 && uint64_t(maxStamp_) < wrapAroundNumber_ * 2u / 3u){
35-
logWarn("Last maxStamp=%u, suspiciously small! Maybe it wraps in fact earlier? (wrapAroundNumber=%lu)", maxStamp_, wrapAroundNumber_);
34+
CUCKOO_TIME_TRANSLATOR_logWarn("Last maxStamp=%u, suspiciously small! Maybe it wraps in fact earlier? (wrapAroundNumber=%lu)", maxStamp_, wrapAroundNumber_);
3635
}
3736
}
3837

0 commit comments

Comments
 (0)