Skip to content

Commit 24237f7

Browse files
committed
Added DeviceTimeTranslator::resetTranslation method.
1 parent be54835 commit 24237f7

File tree

2 files changed

+20
-1
lines changed

2 files changed

+20
-1
lines changed

cuckoo_time_translator/include/cuckoo_time_translator/DeviceTimeTranslator.h

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,6 +116,11 @@ class DeviceTimeTranslator {
116116
* @return the current one way translator. Stays valid until the next update. Can be null.
117117
*/
118118
const OneWayTranslator * getCurrentOwt() const;
119+
120+
/**
121+
* Reset the translation state while keeping the expected settings such as expected algorithm or switch time.
122+
*/
123+
void resetTranslation();
119124
private:
120125
void configCallback(DeviceTimeTranslatorConfig &config, uint32_t level);
121126

@@ -153,7 +158,7 @@ class DeviceTimeUnwrapperAndTranslator {
153158

154159
ros::Time translate(UnwrappedStamp unwrappedStamp) const;
155160
bool isReadyToTranslate() const;
156-
161+
157162
FilterAlgorithm getCurrentFilterAlgorithm() const {
158163
return translator.getCurrentFilterAlgorithm();
159164
}
@@ -176,6 +181,13 @@ class DeviceTimeUnwrapperAndTranslator {
176181
const OneWayTranslator* getCurrentOwt() const {
177182
return translator.getCurrentOwt();
178183
}
184+
185+
/**
186+
* Reset the translation state while keeping the expected settings such as expected algorithm or switch time.
187+
*/
188+
void resetTranslation() {
189+
translator.resetTranslation();
190+
}
179191
protected:
180192
Unwrapper timestampUnwrapper;
181193
DeviceTimeTranslator translator;

cuckoo_time_translator/src/DeviceTimeTranslator.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -205,6 +205,9 @@ class DeviceTimeTranslator::Impl {
205205
return timeTranslator_.get();
206206
}
207207

208+
void resetTranslation() {
209+
timeTranslator_.reset();
210+
}
208211
private:
209212

210213
template <typename Owt>
@@ -310,6 +313,10 @@ void DeviceTimeTranslator::setFilterAlgorithm(FilterAlgorithm filterAlgorithm) {
310313
pImpl_->setExpectedAlgo(filterAlgorithm);
311314
}
312315

316+
void DeviceTimeTranslator::resetTranslation() {
317+
pImpl_->resetTranslation();
318+
}
319+
313320
ros::Time DeviceTimeTranslator::update(const TimestampUnwrapper & timestampUnwrapper, const ros::Time & receiveTime, const double offsetSecs) {
314321
if(!pImpl_) return receiveTime;
315322

0 commit comments

Comments
 (0)