Class ActiveTimeCorrection

Class Documentation

class ActiveTimeCorrection

Class to handle active time correction for LidarScans.

This class provides methods to correct and reset timestamps in LidarScans based on sensor information. It checks for synchronization between sensors, ensures monotonicity of timestamps, and applies corrections as needed.

Typical usage pattern: ActiveTimeCorrection time_correction(infos);

for (auto scans : scan_source) { time_correction.update(scans); // to apply time correction slam_engine.update(scans); // SLAM processing time_correction.reset(scans); // to reset the timestamps }

Public Functions

ActiveTimeCorrection(const std::vector<std::shared_ptr<core::SensorInfo>> &infos)

Construct an ActiveTimeCorrection object from sensor info structures.

Parameters:

infos[in] – A vector of shared pointers to SensorInfo objects, one per sensor.

void update(core::LidarScanSet &scans)

pre-registration scans time check and synchronization.

It modifies the scans by adding corrected timestamp filed. Use the reset() method to remove the added corrected scan timestamps field.

Steps taken: • Compute overall frame timestamp range. • Check inter-sensor synchronization:

  • If sensors are out of sync, enable packet-offset mode. • Monotonicity check (ignoring zero timestamps):

  • For any scan whose timestamps go backwards, correct its timestamps and enable packet-offset mode. • Packet-offset handling:

  • If offset mode is active, compute fallback timestamp offsets. • Finally: it detects scans that come out of order.

Remark

when an out of order scan is detected, its range field is zeroed out to invalidate it. This behavior will be revised in the future to avoid modifying the scan data.

Parameters:

scans[inout] – A vector of shared pointers to LidarScan objects to be processed.

void reset(core::LidarScanSet &scans)

reset scans sensor time post-registration

Parameters:

scans[inout] – A vector of shared pointers to LidarScan objects to be processed.

inline std::vector<std::pair<int64_t, int64_t>> &last_frame_ts_range()

get frame ts ranges

Returns:

vector of (start_ts, end_ts) pairs for each scan within the scan set

bool check_sensors_synchronization(const std::vector<std::pair<int64_t, int64_t>> &frame_ts_range) const

Determines whether a set of lidar scans are pre-synchronized based on their start timestamps.

This function compares the earliest and latest start timestamps from a range of scans and checks if their difference is within the smallest frame duration available. If the time difference is less than or equal to the minimum frame gap, the scans are considered pre-synchronized.

Parameters:

frame_ts_range[in] – A vector of (start_ts, end_ts) pairs representing the time value range for each scan.

Returns:

true if the scans are pre-synchronized, false otherwise.

void correct_scan_ts(core::LidarScan &scan, size_t sensor_idx)

Corrects the timestamps of the input Lidar scan based on the previous frame’s timestamp range and the sensor’s frame duration.

Parameters:
  • scan[inout] – The LidarScan object whose timestamps need to be corrected.

  • sensor_idx[in] – The index of the sensor associated with the scan.

Public Static Functions

static bool is_monotonically_increasing(Eigen::Ref<const core::LidarScan::Header<uint64_t>> timestamps, int64_t last_frame_stop_ts)

Checks if the timestamps in each lidar scan are strictly increasing (ignoring any zeros) and its first non-zero timestamp is greater than the previous frame’s end timestamp.

Parameters:
  • timestamps[in] – a vector representing lidar timestamps.

  • last_frame_stop_ts[in] – The end timestamp of the previous frame.

Returns:

true if the input timestamps are monotonically increasing, false otherwise.