#include <TimestampSynchronizer.h>
Classes | |
class | Options |
Public Member Functions | |
void | reset () |
void | setAlfa_HoltWinters (double alfa_HoltWinters) |
void | setAlfa_HoltWinters_early (double alfa_HoltWinters_early) |
void | setBeta_HoltWinters (double beta_HoltWinters) |
void | setBeta_HoltWinters_early (double beta_HoltWinters_early) |
void | setEarlyClamp (bool earlyClamp, int earlyClampWindow=0) |
void | setMedianFilter (bool useMedianFilter, int medianFilterWindow=0) |
void | setTimeOffset (double timeOffset) |
void | setUseHoltWinters (bool useHoltWinters) |
double | sync (double currentSensorTime, double currentRosTime, unsigned int seqNumber_external) |
TimestampSynchronizer (const Options defaultOptions=Options()) | |
Private Member Functions | |
void | init () |
void | initMediator () |
Private Attributes | |
ros::Publisher | debugPublisher_ |
bool | firstFrameSet_ |
HoltWintersSmoothFilter | holtWinters_ |
ros::NodeHandle | np_ |
Options | options_ |
std::unique_ptr< Mediator< double > > | pmediator_ |
double | previousOut_ |
double | previousRosTime_ |
double | previousSensorTime_ |
unsigned int | seqCounter_ |
double | startRosTimeBig_ |
double | startSensorTime_ |
The timestamp synchronization functionality is implemented in this class
Definition at line 38 of file TimestampSynchronizer.h.
The constructor of the TimestampSynchronizer class accepts default options which will be used if the corresponding ROS parameters are not defined
Definition at line 6 of file TimestampSynchronizer.cpp.
|
private |
Definition at line 160 of file TimestampSynchronizer.cpp.
|
private |
Definition at line 156 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::reset | ( | ) |
Reset the state of the TimestampSynchronizer, including the states of the Median and Holt-Winters filters.
Definition at line 151 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setAlfa_HoltWinters | ( | double | alfa_HoltWinters | ) |
Definition at line 135 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setAlfa_HoltWinters_early | ( | double | alfa_HoltWinters_early | ) |
Definition at line 143 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setBeta_HoltWinters | ( | double | beta_HoltWinters | ) |
Definition at line 139 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setBeta_HoltWinters_early | ( | double | beta_HoltWinters_early | ) |
Definition at line 147 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setEarlyClamp | ( | bool | earlyClamp, |
int | earlyClampWindow = 0 |
||
) |
Definition at line 166 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setMedianFilter | ( | bool | useMedianFilter, |
int | medianFilterWindow = 0 |
||
) |
Definition at line 125 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setTimeOffset | ( | double | timeOffset | ) |
Definition at line 121 of file TimestampSynchronizer.cpp.
void TimestampSynchronizer::setUseHoltWinters | ( | bool | useHoltWinters | ) |
Definition at line 131 of file TimestampSynchronizer.cpp.
double TimestampSynchronizer::sync | ( | double | currentSensorTime, |
double | currentRosTime, | ||
unsigned int | seqNumber_external | ||
) |
Accept a reading from the sensor and computer clocks, along with the sequence number, and calculate a corrected timestamp for the sensor reading.
currentSensorTime | Time of the current reading, as reported by the sensor. |
currentRosTime | Time of the current reading, as read from the system clock. |
seqNumber_external | Sequence number of the current reading. Used for logging purposes only (e.g. to examine if frame drops have occured). TimestampSynchronizer keeps its own internal sequence counter. |
Definition at line 44 of file TimestampSynchronizer.cpp.
|
private |
Definition at line 115 of file TimestampSynchronizer.h.
|
private |
Definition at line 109 of file TimestampSynchronizer.h.
|
private |
Definition at line 107 of file TimestampSynchronizer.h.
|
private |
Definition at line 114 of file TimestampSynchronizer.h.
|
private |
Definition at line 117 of file TimestampSynchronizer.h.
|
private |
Definition at line 106 of file TimestampSynchronizer.h.
|
private |
Definition at line 102 of file TimestampSynchronizer.h.
|
private |
Definition at line 102 of file TimestampSynchronizer.h.
|
private |
Definition at line 102 of file TimestampSynchronizer.h.
|
private |
Definition at line 110 of file TimestampSynchronizer.h.
|
private |
Definition at line 104 of file TimestampSynchronizer.h.
|
private |
Definition at line 105 of file TimestampSynchronizer.h.