Skip to content

evalio.datasets

For more information about the datasets included in evalio, see the included datasets section.

Classes:

  • Dataset

    The base class for all datasets.

  • DatasetIterator

    This is the base class for iterating over datasets.

  • RawDataIter

    An iterator for loading from python iterables.

  • RosbagIter

    An iterator for loading from rosbag files.

  • BotanicGarden

    Dataset taken from a botanical garden, specifically for testing unstructured environments. Ground truth is gathered using a survey grade lidar.

  • CUMulti

    Dataset collected by a ground robot (AgileX - Hunter) on the University of Colorado Boulder Campus.

  • EnWide

    Dataset taken in purposely degenerate locations such as a field, intersections, tunnels, and runways. All data comes directly from the Ouster unit.

  • HeLiPR

    Self-driving car dataset taken in urban environments. Ground truth is generated using filtering of an RTK-GNSS system.

  • Hilti2022

    Sequences with ground truth taken from the Hilti 2022 SLAM Challenge, mostly taken from indoors.

  • MultiCampus

    Data taken from a variety of campus (KTH, NTU, TUHH) in Asia and Europe at different seasons, at day and night, and with an ATV and handheld platform.

  • NewerCollege2020

    Dataset taken from outdoor Oxford Campus. Ground truth is generated using ICP matching against a laser scanner.

  • NewerCollege2021

    Dataset outdoors on oxford campus with a handheld device consisting of an alphasense core and a Ouster lidar.

  • OxfordSpires

    Dataset taken both indoors and outdoors on the Oxford campus.

  • DatasetNotFound

    Exception raised when a dataset is not found.

  • SequenceNotFound

    Exception raised when a sequence is not found.

Functions:

  • get_data_dir

    Get the global data directory. This is where downloaded data is stored.

  • set_data_dir

    Set the global location where datasets are stored. This will be used to store the downloaded data.

  • all_datasets

    Get all registered datasets.

  • get_dataset

    Get a registered dataset by name.

  • all_sequences

    Get all sequences from all registered datasets.

  • get_sequence

    Get a registered sequence by name.

  • register_dataset

    Register a dataset.

Dataset

Bases: StrEnum

The base class for all datasets.

This class provides an interface for loading datasets, including loading parameters and iterating over measurements. All datasets are string enums, where each enum member represents a trajectory sequence in the dataset.

Methods:

  • data_iter

    Provides an iterator over the dataset's measurements.

  • ground_truth_raw

    Retrieves the raw ground truth trajectory, as represented in the ground truth frame.

  • imu_T_lidar

    Returns the transformation from IMU to Lidar frame.

  • imu_T_gt

    Retrieves the transformation from IMU to ground truth frame.

  • imu_params

    Specifies the parameters of the IMU.

  • lidar_params

    Specifies the parameters of the Lidar.

  • files

    Return list of files required to run this dataset.

  • url

    Webpage with the dataset information.

  • environment

    Environment where the dataset was collected.

  • vehicle

    Vehicle used to collect the dataset.

  • quick_len

    Hardcoded number of lidar scans in the dataset, rather than computing by loading all the data (slow).

  • download

    Method to download the dataset.

  • dataset_name

    Name of the dataset, in snake case.

  • is_downloaded

    Verify if the dataset is downloaded.

  • ground_truth

    Get the ground truth trajectory in the IMU frame, rather than the ground truth frame as returned in ground_truth_raw.

  • __len__

    Return the number of lidar scans.

  • __iter__

    Main interface for iterating over measurements of all types.

  • imu

    Iterate over just IMU measurements.

  • lidar

    Iterate over just Lidar measurements.

  • get_one_lidar

    Get a single Lidar measurement.

  • get_one_imu

    Get a single IMU measurement.

  • sequences

    All sequences in the dataset.

  • size_on_disk

    Shows the size of the dataset on disk, in GB.

Attributes:

  • seq_name (str) –

    Name of the sequence, in snake case.

  • full_name (str) –

    Full name of the dataset, including the dataset name and sequence name.

  • folder (Path) –

    The folder in the global dataset directory where this dataset is stored.

Source code in python/evalio/datasets/base.py
class Dataset(StrEnum):
    """The base class for all datasets.

    This class provides an interface for loading datasets, including loading parameters and iterating over measurements.
    All datasets are string enums, where each enum member represents a trajectory sequence in the dataset.
    """

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        """
        Provides an iterator over the dataset's measurements.

        Returns:
            An iterator that yields measurements from the dataset.
        """
        ...

    # Return the ground truth in the ground truth frame
    def ground_truth_raw(self) -> Trajectory:
        """
        Retrieves the raw ground truth trajectory, as represented in the ground truth frame.

        Returns:
            The raw ground truth trajectory data.
        """
        ...

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        """Returns the transformation from IMU to Lidar frame.

        Returns:
            Transformation from IMU to Lidar frame.
        """
        ...

    def imu_T_gt(self) -> SE3:
        """Retrieves the transformation from IMU to ground truth frame.

        Returns:
            Transformation from IMU to ground truth frame.
        """
        ...

    def imu_params(self) -> ImuParams:
        """Specifies the parameters of the IMU.

        Returns:
            Parameters of the IMU.
        """
        ...

    def lidar_params(self) -> LidarParams:
        """Specifies the parameters of the Lidar.

        Returns:
            Parameters of the Lidar.
        """
        ...

    def files(self) -> Sequence[str | Path]:
        """Return list of files required to run this dataset.

        If a returned type is a Path, it will be checked as is. If it is a string, it will be prepended with [folder][evalio.datasets.Dataset.folder].

        Returns:
            List of files required to run this dataset.
        """
        ...

    # ------------------------- Optional dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        """Webpage with the dataset information.

        Returns:
            URL of the dataset webpage.
        """
        return "-"

    def environment(self) -> str:
        """Environment where the dataset was collected.

        Returns:
            Environment where the dataset was collected.
        """
        return "-"

    def vehicle(self) -> str:
        """Vehicle used to collect the dataset.

        Returns:
            Vehicle used to collect the dataset.
        """
        return "-"

    def quick_len(self) -> Optional[int]:
        """Hardcoded number of lidar scans in the dataset, rather than computing by loading all the data (slow).

        Returns:
            Number of lidar scans in the dataset. None if not available.
        """
        return None

    def download(self) -> None:
        """Method to download the dataset.

        Completely optional to implement, although most datasets do.

        Raises:
            NotImplementedError: If not implemented.
        """
        raise NotImplementedError("Download not implemented")

    # TODO: This would match better as a "classproperty", but not will involve some work
    @classmethod
    def dataset_name(cls) -> str:
        """Name of the dataset, in snake case.

        This is the name that will be used when parsing directly from a string. Currently is automatically generated from the class name, but can be overridden.

        Returns:
            Name of the dataset.
        """
        return pascal_to_snake(cls.__name__)

    # ------------------------- Helpers that wrap the above ------------------------- #
    def is_downloaded(self) -> bool:
        """Verify if the dataset is downloaded.

        Returns:
            True if the dataset is downloaded, False otherwise.
        """
        self._warn_default_dir()
        for f in self.files():
            if isinstance(f, str):
                if not (self.folder / f).exists():
                    return False
            else:
                if not f.exists():
                    return False

        return True

    def ground_truth(self) -> Trajectory[GroundTruth]:
        """Get the ground truth trajectory in the **IMU** frame, rather than the ground truth frame as returned in [ground_truth_raw][evalio.datasets.Dataset.ground_truth_raw].

        Returns:
            The ground truth trajectory in the IMU frame.
        """
        gt_traj = self.ground_truth_raw()
        gt_T_imu = self.imu_T_gt().inverse()

        # Convert to IMU frame
        for i in range(len(gt_traj)):
            gt_o_T_gt_i = gt_traj.poses[i]
            gt_traj.poses[i] = gt_o_T_gt_i * gt_T_imu

        gt_traj = cast(Trajectory[GroundTruth], gt_traj)
        gt_traj.metadata = GroundTruth(sequence=self.full_name)

        return gt_traj

    def _fail_not_downloaded(self):
        if not self.is_downloaded():
            # TODO: Make this print with rich?
            raise ValueError(
                f"Data for {self} not found, please use `evalio download {self}` to download"
            )

    @classmethod
    def _warn_default_dir(cls):
        global _DATA_DIR, _WARNED
        if not _WARNED and _DATA_DIR == Path("./evalio_data"):
            print_warning(
                "Using default './evalio_data' for base data directory. Override by setting [magenta]EVALIO_DATA[/magenta], [magenta]evalio.set_data_dir(path)[/magenta] in python, or [magenta]-D[/magenta] in the CLI."
            )
            _WARNED = True

    # ------------------------- Helpers that leverage from the iterator ------------------------- #

    def __len__(self) -> int:
        """Return the number of lidar scans.

        If quick_len is available, it will be used. Otherwise, it will load the entire dataset to get the length.

        Returns:
            Number of lidar scans.
        """
        if (length := self.quick_len()) is not None:
            return length

        self._fail_not_downloaded()
        return self.data_iter().__len__()

    def __iter__(self) -> Iterator[Measurement]:  # type: ignore
        """Main interface for iterating over measurements of all types.

        Returns:
            Iterator of all measurements (IMU and Lidar).
        """
        self._fail_not_downloaded()
        return self.data_iter().__iter__()

    def imu(self) -> Iterable[ImuMeasurement]:
        """Iterate over just IMU measurements.

        Returns:
            Iterator of IMU measurements.
        """
        self._fail_not_downloaded()
        return self.data_iter().imu_iter()

    def lidar(self) -> Iterable[LidarMeasurement]:
        """Iterate over just Lidar measurements.

        Returns:
            Iterator of Lidar measurements.
        """
        self._fail_not_downloaded()
        return self.data_iter().lidar_iter()

    def get_one_lidar(self, idx: int = 0) -> LidarMeasurement:
        """Get a single Lidar measurement.

        Note, this can be expensive to compute, as it will iterate over the entire dataset until it finds the measurement.

        Args:
            idx (int, optional): Index of measurement to get. Defaults to 0.

        Returns:
            The Lidar measurement at the given index.
        """
        return next(islice(self.lidar(), idx, idx + 1))

    def get_one_imu(self, idx: int = 0) -> ImuMeasurement:
        """Get a single IMU measurement.

        Note, this can be expensive to compute, as it will iterate over the entire dataset until it finds the measurement.

        Args:
            idx (int, optional): Index of measurement to get. Defaults to 0.

        Returns:
            The IMU measurement at the given index.
        """
        return next(islice(self.imu(), idx, idx + 1))

    # ------------------------- Misc name helpers ------------------------- #
    def __str__(self):
        return self.full_name

    @property
    def seq_name(self) -> str:
        """Name of the sequence, in snake case.

        Returns:
            Name of the sequence.
        """
        return self.value

    @property
    def full_name(self) -> str:
        """Full name of the dataset, including the dataset name and sequence name.

        Example: "dataset_name/sequence_name"

        Returns:
            Full name of the dataset.
        """
        return f"{self.dataset_name()}/{self.seq_name}"

    @classmethod
    def sequences(cls) -> list["Dataset"]:
        """All sequences in the dataset.

        Returns:
            List of all sequences in the dataset.
        """
        return list(cls.__members__.values())

    @property
    def folder(self) -> Path:
        """The folder in the global dataset directory where this dataset is stored.

        Returns:
            Path to the dataset folder.
        """
        global _DATA_DIR
        return _DATA_DIR / self.full_name

    def size_on_disk(self) -> Optional[float]:
        """Shows the size of the dataset on disk, in GB.

        Returns:
            Size of the dataset on disk, in GB. None if the dataset is not downloaded.
        """

        if not self.is_downloaded():
            return None
        else:
            return sum(f.stat().st_size for f in self.folder.glob("**/*")) / 1e9

seq_name property

seq_name: str

Name of the sequence, in snake case.

Returns:

  • str

    Name of the sequence.

full_name property

full_name: str

Full name of the dataset, including the dataset name and sequence name.

Example: "dataset_name/sequence_name"

Returns:

  • str

    Full name of the dataset.

folder property

folder: Path

The folder in the global dataset directory where this dataset is stored.

Returns:

  • Path

    Path to the dataset folder.

data_iter

data_iter() -> DatasetIterator

Provides an iterator over the dataset's measurements.

Returns:

  • DatasetIterator

    An iterator that yields measurements from the dataset.

Source code in python/evalio/datasets/base.py
def data_iter(self) -> DatasetIterator:
    """
    Provides an iterator over the dataset's measurements.

    Returns:
        An iterator that yields measurements from the dataset.
    """
    ...

ground_truth_raw

ground_truth_raw() -> Trajectory

Retrieves the raw ground truth trajectory, as represented in the ground truth frame.

Returns:

  • Trajectory

    The raw ground truth trajectory data.

Source code in python/evalio/datasets/base.py
def ground_truth_raw(self) -> Trajectory:
    """
    Retrieves the raw ground truth trajectory, as represented in the ground truth frame.

    Returns:
        The raw ground truth trajectory data.
    """
    ...

imu_T_lidar

imu_T_lidar() -> SE3

Returns the transformation from IMU to Lidar frame.

Returns:

  • SE3

    Transformation from IMU to Lidar frame.

Source code in python/evalio/datasets/base.py
def imu_T_lidar(self) -> SE3:
    """Returns the transformation from IMU to Lidar frame.

    Returns:
        Transformation from IMU to Lidar frame.
    """
    ...

imu_T_gt

imu_T_gt() -> SE3

Retrieves the transformation from IMU to ground truth frame.

Returns:

  • SE3

    Transformation from IMU to ground truth frame.

Source code in python/evalio/datasets/base.py
def imu_T_gt(self) -> SE3:
    """Retrieves the transformation from IMU to ground truth frame.

    Returns:
        Transformation from IMU to ground truth frame.
    """
    ...

imu_params

imu_params() -> ImuParams

Specifies the parameters of the IMU.

Returns:

Source code in python/evalio/datasets/base.py
def imu_params(self) -> ImuParams:
    """Specifies the parameters of the IMU.

    Returns:
        Parameters of the IMU.
    """
    ...

lidar_params

lidar_params() -> LidarParams

Specifies the parameters of the Lidar.

Returns:

Source code in python/evalio/datasets/base.py
def lidar_params(self) -> LidarParams:
    """Specifies the parameters of the Lidar.

    Returns:
        Parameters of the Lidar.
    """
    ...

files

files() -> Sequence[str | Path]

Return list of files required to run this dataset.

If a returned type is a Path, it will be checked as is. If it is a string, it will be prepended with folder.

Returns:

  • Sequence[str | Path]

    List of files required to run this dataset.

Source code in python/evalio/datasets/base.py
def files(self) -> Sequence[str | Path]:
    """Return list of files required to run this dataset.

    If a returned type is a Path, it will be checked as is. If it is a string, it will be prepended with [folder][evalio.datasets.Dataset.folder].

    Returns:
        List of files required to run this dataset.
    """
    ...

url staticmethod

url() -> str

Webpage with the dataset information.

Returns:

  • str

    URL of the dataset webpage.

Source code in python/evalio/datasets/base.py
@staticmethod
def url() -> str:
    """Webpage with the dataset information.

    Returns:
        URL of the dataset webpage.
    """
    return "-"

environment

environment() -> str

Environment where the dataset was collected.

Returns:

  • str

    Environment where the dataset was collected.

Source code in python/evalio/datasets/base.py
def environment(self) -> str:
    """Environment where the dataset was collected.

    Returns:
        Environment where the dataset was collected.
    """
    return "-"

vehicle

vehicle() -> str

Vehicle used to collect the dataset.

Returns:

  • str

    Vehicle used to collect the dataset.

Source code in python/evalio/datasets/base.py
def vehicle(self) -> str:
    """Vehicle used to collect the dataset.

    Returns:
        Vehicle used to collect the dataset.
    """
    return "-"

quick_len

quick_len() -> Optional[int]

Hardcoded number of lidar scans in the dataset, rather than computing by loading all the data (slow).

Returns:

  • Optional[int]

    Number of lidar scans in the dataset. None if not available.

Source code in python/evalio/datasets/base.py
def quick_len(self) -> Optional[int]:
    """Hardcoded number of lidar scans in the dataset, rather than computing by loading all the data (slow).

    Returns:
        Number of lidar scans in the dataset. None if not available.
    """
    return None

download

download() -> None

Method to download the dataset.

Completely optional to implement, although most datasets do.

Raises:

  • NotImplementedError

    If not implemented.

Source code in python/evalio/datasets/base.py
def download(self) -> None:
    """Method to download the dataset.

    Completely optional to implement, although most datasets do.

    Raises:
        NotImplementedError: If not implemented.
    """
    raise NotImplementedError("Download not implemented")

dataset_name classmethod

dataset_name() -> str

Name of the dataset, in snake case.

This is the name that will be used when parsing directly from a string. Currently is automatically generated from the class name, but can be overridden.

Returns:

  • str

    Name of the dataset.

Source code in python/evalio/datasets/base.py
@classmethod
def dataset_name(cls) -> str:
    """Name of the dataset, in snake case.

    This is the name that will be used when parsing directly from a string. Currently is automatically generated from the class name, but can be overridden.

    Returns:
        Name of the dataset.
    """
    return pascal_to_snake(cls.__name__)

is_downloaded

is_downloaded() -> bool

Verify if the dataset is downloaded.

Returns:

  • bool

    True if the dataset is downloaded, False otherwise.

Source code in python/evalio/datasets/base.py
def is_downloaded(self) -> bool:
    """Verify if the dataset is downloaded.

    Returns:
        True if the dataset is downloaded, False otherwise.
    """
    self._warn_default_dir()
    for f in self.files():
        if isinstance(f, str):
            if not (self.folder / f).exists():
                return False
        else:
            if not f.exists():
                return False

    return True

ground_truth

ground_truth() -> Trajectory[GroundTruth]

Get the ground truth trajectory in the IMU frame, rather than the ground truth frame as returned in ground_truth_raw.

Returns:

Source code in python/evalio/datasets/base.py
def ground_truth(self) -> Trajectory[GroundTruth]:
    """Get the ground truth trajectory in the **IMU** frame, rather than the ground truth frame as returned in [ground_truth_raw][evalio.datasets.Dataset.ground_truth_raw].

    Returns:
        The ground truth trajectory in the IMU frame.
    """
    gt_traj = self.ground_truth_raw()
    gt_T_imu = self.imu_T_gt().inverse()

    # Convert to IMU frame
    for i in range(len(gt_traj)):
        gt_o_T_gt_i = gt_traj.poses[i]
        gt_traj.poses[i] = gt_o_T_gt_i * gt_T_imu

    gt_traj = cast(Trajectory[GroundTruth], gt_traj)
    gt_traj.metadata = GroundTruth(sequence=self.full_name)

    return gt_traj

__len__

__len__() -> int

Return the number of lidar scans.

If quick_len is available, it will be used. Otherwise, it will load the entire dataset to get the length.

Returns:

  • int

    Number of lidar scans.

Source code in python/evalio/datasets/base.py
def __len__(self) -> int:
    """Return the number of lidar scans.

    If quick_len is available, it will be used. Otherwise, it will load the entire dataset to get the length.

    Returns:
        Number of lidar scans.
    """
    if (length := self.quick_len()) is not None:
        return length

    self._fail_not_downloaded()
    return self.data_iter().__len__()

__iter__

__iter__() -> Iterator[Measurement]

Main interface for iterating over measurements of all types.

Returns:

  • Iterator[Measurement]

    Iterator of all measurements (IMU and Lidar).

Source code in python/evalio/datasets/base.py
def __iter__(self) -> Iterator[Measurement]:  # type: ignore
    """Main interface for iterating over measurements of all types.

    Returns:
        Iterator of all measurements (IMU and Lidar).
    """
    self._fail_not_downloaded()
    return self.data_iter().__iter__()

imu

imu() -> Iterable[ImuMeasurement]

Iterate over just IMU measurements.

Returns:

Source code in python/evalio/datasets/base.py
def imu(self) -> Iterable[ImuMeasurement]:
    """Iterate over just IMU measurements.

    Returns:
        Iterator of IMU measurements.
    """
    self._fail_not_downloaded()
    return self.data_iter().imu_iter()

lidar

lidar() -> Iterable[LidarMeasurement]

Iterate over just Lidar measurements.

Returns:

Source code in python/evalio/datasets/base.py
def lidar(self) -> Iterable[LidarMeasurement]:
    """Iterate over just Lidar measurements.

    Returns:
        Iterator of Lidar measurements.
    """
    self._fail_not_downloaded()
    return self.data_iter().lidar_iter()

get_one_lidar

get_one_lidar(idx: int = 0) -> LidarMeasurement

Get a single Lidar measurement.

Note, this can be expensive to compute, as it will iterate over the entire dataset until it finds the measurement.

Parameters:

  • idx (int, default: 0 ) –

    Index of measurement to get. Defaults to 0.

Returns:

Source code in python/evalio/datasets/base.py
def get_one_lidar(self, idx: int = 0) -> LidarMeasurement:
    """Get a single Lidar measurement.

    Note, this can be expensive to compute, as it will iterate over the entire dataset until it finds the measurement.

    Args:
        idx (int, optional): Index of measurement to get. Defaults to 0.

    Returns:
        The Lidar measurement at the given index.
    """
    return next(islice(self.lidar(), idx, idx + 1))

get_one_imu

get_one_imu(idx: int = 0) -> ImuMeasurement

Get a single IMU measurement.

Note, this can be expensive to compute, as it will iterate over the entire dataset until it finds the measurement.

Parameters:

  • idx (int, default: 0 ) –

    Index of measurement to get. Defaults to 0.

Returns:

Source code in python/evalio/datasets/base.py
def get_one_imu(self, idx: int = 0) -> ImuMeasurement:
    """Get a single IMU measurement.

    Note, this can be expensive to compute, as it will iterate over the entire dataset until it finds the measurement.

    Args:
        idx (int, optional): Index of measurement to get. Defaults to 0.

    Returns:
        The IMU measurement at the given index.
    """
    return next(islice(self.imu(), idx, idx + 1))

sequences classmethod

sequences() -> list[Dataset]

All sequences in the dataset.

Returns:

  • list[Dataset]

    List of all sequences in the dataset.

Source code in python/evalio/datasets/base.py
@classmethod
def sequences(cls) -> list["Dataset"]:
    """All sequences in the dataset.

    Returns:
        List of all sequences in the dataset.
    """
    return list(cls.__members__.values())

size_on_disk

size_on_disk() -> Optional[float]

Shows the size of the dataset on disk, in GB.

Returns:

  • Optional[float]

    Size of the dataset on disk, in GB. None if the dataset is not downloaded.

Source code in python/evalio/datasets/base.py
def size_on_disk(self) -> Optional[float]:
    """Shows the size of the dataset on disk, in GB.

    Returns:
        Size of the dataset on disk, in GB. None if the dataset is not downloaded.
    """

    if not self.is_downloaded():
        return None
    else:
        return sum(f.stat().st_size for f in self.folder.glob("**/*")) / 1e9

DatasetIterator

Bases: Iterable[Measurement]

This is the base class for iterating over datasets.

This class is the main interface used to iterate over the dataset's measurements. It provides an interface for iterating over IMU and Lidar measurements, as well as all measurements interleaved. This allows for standardizing access to loading data, while allowing for loading parameters in Dataset without having to load the data. Generally, will be created by the Dataset.data_iter method.

Methods:

  • imu_iter

    Main interface for iterating over IMU measurements.

  • lidar_iter

    Main interface for iterating over Lidar measurements.

  • __iter__

    Main interface for iterating over all measurements.

  • __len__

    Number of lidar scans.

Source code in python/evalio/datasets/base.py
class DatasetIterator(Iterable[Measurement]):
    """This is the base class for iterating over datasets.

    This class is the main interface used to iterate over the dataset's measurements.
    It provides an interface for iterating over IMU and Lidar measurements, as well as all measurements interleaved.
    This allows for standardizing access to loading data, while allowing for loading parameters in [Dataset][evalio.datasets.Dataset] without having to load the data.
    Generally, will be created by the [Dataset.data_iter][evalio.datasets.Dataset.data_iter] method.
    """

    def imu_iter(self) -> Iterator[ImuMeasurement]:
        """Main interface for iterating over IMU measurements.

        Yields:
            Iterator of IMU measurements.
        """
        ...

    def lidar_iter(self) -> Iterator[LidarMeasurement]:
        """Main interface for iterating over Lidar measurements.

        Yields:
            Iterator of Lidar measurements.
        """
        ...

    def __iter__(self) -> Iterator[Measurement]:
        """Main interface for iterating over all measurements.

        Yields:
            Iterator of all measurements (IMU and Lidar).
        """

        ...

    # Return the number of lidar scans
    def __len__(self) -> int:
        """Number of lidar scans.

        Returns:
            Number of lidar scans.
        """
        ...

imu_iter

imu_iter() -> Iterator[ImuMeasurement]

Main interface for iterating over IMU measurements.

Yields:

Source code in python/evalio/datasets/base.py
def imu_iter(self) -> Iterator[ImuMeasurement]:
    """Main interface for iterating over IMU measurements.

    Yields:
        Iterator of IMU measurements.
    """
    ...

lidar_iter

lidar_iter() -> Iterator[LidarMeasurement]

Main interface for iterating over Lidar measurements.

Yields:

Source code in python/evalio/datasets/base.py
def lidar_iter(self) -> Iterator[LidarMeasurement]:
    """Main interface for iterating over Lidar measurements.

    Yields:
        Iterator of Lidar measurements.
    """
    ...

__iter__

__iter__() -> Iterator[Measurement]

Main interface for iterating over all measurements.

Yields:

  • Measurement

    Iterator of all measurements (IMU and Lidar).

Source code in python/evalio/datasets/base.py
def __iter__(self) -> Iterator[Measurement]:
    """Main interface for iterating over all measurements.

    Yields:
        Iterator of all measurements (IMU and Lidar).
    """

    ...

__len__

__len__() -> int

Number of lidar scans.

Returns:

  • int

    Number of lidar scans.

Source code in python/evalio/datasets/base.py
def __len__(self) -> int:
    """Number of lidar scans.

    Returns:
        Number of lidar scans.
    """
    ...

RawDataIter

Bases: DatasetIterator

An iterator for loading from python iterables.

Interleaves imu and lidar iterables. Allows for arbitrary data to be loaded and presented in a consistent manner for the base Dataset class. Has identical methods to DatasetIterator.

Methods:

Source code in python/evalio/datasets/loaders.py
class RawDataIter(DatasetIterator):
    """An iterator for loading from python iterables.

    Interleaves imu and lidar iterables. Allows for arbitrary data to be loaded and presented in a consistent manner for the base [Dataset][evalio.datasets.Dataset] class.
    Has identical methods to [DatasetIterator][evalio.datasets.DatasetIterator].
    """

    T = TypeVar("T", ImuMeasurement, LidarMeasurement)

    def __init__(
        self,
        iter_lidar: Iterator[LidarMeasurement],
        iter_imu: Iterator[ImuMeasurement],
        num_lidar: int,
    ):
        """
        Args:
            iter_lidar (Iterator[LidarMeasurement]): An iterator over LidarMeasurement
            iter_imu (Iterator[ImuMeasurement]): An iterator over ImuMeasurement
            num_lidar (int): The number of lidar measurements

        ``` py
        from evalio.datasets.loaders import RawDataIter
        from evalio.types import ImuMeasurement, LidarMeasurement, Stamp
        import numpy as np

        # Create some fake data
        imu_iter = (
            ImuMeasurement(Stamp.from_sec(i), np.zeros(3), np.zeros(3))
            for i in range(10)
        )
        lidar_iter = (LidarMeasurement(Stamp.from_sec(i + 0.1)) for i in range(10))

        # Create the iterator
        rawdata = RawDataIter(imu_iter, lidar_iter, 10)
        ```
        """
        self.iter_lidar = iter_lidar
        self.iter_imu = iter_imu
        self.num_lidar = num_lidar
        # These hold the current values for iteration to compare stamps on what should be returned
        self.next_lidar = None
        self.next_imu = None

    def imu_iter(self) -> Iterator[ImuMeasurement]:
        return self.iter_imu

    def lidar_iter(self) -> Iterator[LidarMeasurement]:
        return self.iter_lidar

    def __len__(self) -> int:
        return self.num_lidar

    @staticmethod
    def _step(iter: Iterator[T]) -> Optional[T]:
        try:
            return next(iter)
        except StopIteration:
            return None

    def __iter__(self) -> Iterator[Measurement]:
        self.next_imu = next(self.iter_imu)
        self.next_lidar = next(self.iter_lidar)
        return self

    def __next__(self) -> Measurement:
        # fmt: off
        match (self.next_imu, self.next_lidar):
            case (None, None):
                raise StopIteration
            case (None, _):
                to_return, self.next_lidar = self.next_lidar, self._step(self.iter_lidar)
                return to_return
            case (_, None):
                to_return, self.next_imu = self.next_imu, self._step(self.iter_imu)
                return to_return
            case (imu, lidar):
                if imu.stamp < lidar.stamp:
                    to_return, self.next_imu = self.next_imu, self._step(self.iter_imu)
                    return to_return
                else:
                    to_return, self.next_lidar = self.next_lidar, self._step(self.iter_lidar)
                    return to_return

__init__

__init__(
    iter_lidar: Iterator[LidarMeasurement],
    iter_imu: Iterator[ImuMeasurement],
    num_lidar: int,
)

Parameters:

  • iter_lidar (Iterator[LidarMeasurement]) –

    An iterator over LidarMeasurement

  • iter_imu (Iterator[ImuMeasurement]) –

    An iterator over ImuMeasurement

  • num_lidar (int) –

    The number of lidar measurements

from evalio.datasets.loaders import RawDataIter
from evalio.types import ImuMeasurement, LidarMeasurement, Stamp
import numpy as np

# Create some fake data
imu_iter = (
    ImuMeasurement(Stamp.from_sec(i), np.zeros(3), np.zeros(3))
    for i in range(10)
)
lidar_iter = (LidarMeasurement(Stamp.from_sec(i + 0.1)) for i in range(10))

# Create the iterator
rawdata = RawDataIter(imu_iter, lidar_iter, 10)
Source code in python/evalio/datasets/loaders.py
def __init__(
    self,
    iter_lidar: Iterator[LidarMeasurement],
    iter_imu: Iterator[ImuMeasurement],
    num_lidar: int,
):
    """
    Args:
        iter_lidar (Iterator[LidarMeasurement]): An iterator over LidarMeasurement
        iter_imu (Iterator[ImuMeasurement]): An iterator over ImuMeasurement
        num_lidar (int): The number of lidar measurements

    ``` py
    from evalio.datasets.loaders import RawDataIter
    from evalio.types import ImuMeasurement, LidarMeasurement, Stamp
    import numpy as np

    # Create some fake data
    imu_iter = (
        ImuMeasurement(Stamp.from_sec(i), np.zeros(3), np.zeros(3))
        for i in range(10)
    )
    lidar_iter = (LidarMeasurement(Stamp.from_sec(i + 0.1)) for i in range(10))

    # Create the iterator
    rawdata = RawDataIter(imu_iter, lidar_iter, 10)
    ```
    """
    self.iter_lidar = iter_lidar
    self.iter_imu = iter_imu
    self.num_lidar = num_lidar
    # These hold the current values for iteration to compare stamps on what should be returned
    self.next_lidar = None
    self.next_imu = None

RosbagIter

Bases: DatasetIterator

An iterator for loading from rosbag files.

This is a wrapper around the rosbags library, with some niceties for converting ros PointCloud2 messages to a standardized format. Has identical methods to DatasetIterator.

Methods:

Source code in python/evalio/datasets/loaders.py
class RosbagIter(DatasetIterator):
    """An iterator for loading from rosbag files.

    This is a wrapper around the rosbags library, with some niceties for converting ros PointCloud2 messages to a standardized format.
    Has identical methods to [DatasetIterator][evalio.datasets.DatasetIterator].
    """

    def __init__(
        self,
        path: Path,
        lidar_topic: str,
        imu_topic: str,
        lidar_params: LidarParams,
        type_store: Optional[Stores] = None,
        # Reduce compute by telling the iterator how to format the pointcloud
        lidar_format: Optional[LidarFormatParams] = None,
        custom_col_func: Optional[Callable[[LidarMeasurement], None]] = None,
    ):
        """
        Args:
            path (Path): Location of rosbag file(s) or dir(s). If a directory is passed containing multiple bags (ros1 or ros2), all will be loaded.
            lidar_topic (str): Name of lidar topic.
            imu_topic (str): Name of imu topic.
            lidar_params (LidarParams): Lidar parameters, can be gotten from [lidar_params][evalio.datasets.Dataset.lidar_params].
            type_store (Optional[Stores], optional): Additional type store to be loaded into rosbags. Defaults to None.
            lidar_format (Optional[LidarFormatParams], optional): Various parameters for how lidar data is stored. If not specified, most will try to be inferred. We strongly recommend setting this to ensure data is standardized properly. Defaults to None.
            custom_col_func (Optional[Callable[[LidarMeasurement], None]], optional): Function to put the point cloud in row major format. Will generally not be needed, except for strange default orderings. Defaults to None.

        Raises:
            FileNotFoundError: If the path is a directory and no .bag files are found.
            ValueError: If the lidar or imu topic is not found in the bag file.
        """
        self.lidar_topic = lidar_topic
        self.imu_topic = imu_topic
        self.lidar_params = lidar_params
        if lidar_format is None:
            self.lidar_format = LidarFormatParams()
        else:
            self.lidar_format = lidar_format
        self.custom_col_func = custom_col_func

        # Find all bags (may be either ros1 .bag files or ros2 bag/ dirs)
        if path.is_file():
            # Provide path is a ros1 .bag file
            self.path = [path]
        else:

            def is_ros2_bag(d: Path) -> bool:
                return bool(list(d.glob("*.mcap")) + list(d.glob("*.db3")))

            # Path provided is a directory may be ros2 bag/ dir or contain multiple bags
            ros1_bag_file_list = [p for p in path.glob("*.bag")]
            ros2_bag_dir_list = [d for d in path.glob("*/") if is_ros2_bag(d)]

            if ros1_bag_file_list:  # path contains ros1 .bag files
                self.path = ros1_bag_file_list
            elif ros2_bag_dir_list:  # path contains ros2 bag/ directories
                self.path = ros2_bag_dir_list
            elif is_ros2_bag(path):  # path is a ros2 bag/ (contains mcap or db3 file)
                self.path = [path]
            else:
                raise ValueError(
                    f"Invalid rosbag path: {path}\nExpected path to be one of:\na) ros1 .bag \nb) ros2 bag/ dir or \nc) directory multiple a or b"
                )

        # Open the bag file
        self.reader = AnyReader(self.path)
        self.reader.open()

        # force load passed in type store
        # there is a default_typestore parameter in AnyReader, but it won't be used if one of bags has msgdefs
        # this works around that, but may be unstable
        # https://gitlab.com/ternaris/rosbags/-/blob/master/src/rosbags/highlevel/anyreader.py?ref_type=heads#L125-140
        if type_store is not None:
            self.reader.typestore.register(get_typestore(type_store).fielddefs)

        self.connections_lidar = [
            x for x in self.reader.connections if x.topic == self.lidar_topic
        ]
        self.connections_imu = [
            x for x in self.reader.connections if x.topic == self.imu_topic
        ]

        if len(self.connections_imu) == 0 or len(self.connections_lidar) == 0:
            table = Table(title="Rosbag Connections", highlight=True, box=box.ROUNDED)
            table.add_column("Topic", justify="right")
            table.add_column("MsgType", justify="left")
            for c in self.reader.connections:
                table.add_row(c.topic, c.msgtype)
            Console().print(table)

            if len(self.connections_imu) == 0:
                raise ValueError(f"Could not find topic {self.imu_topic}")
            if len(self.connections_lidar) == 0:
                raise ValueError(f"Could not find topic {self.lidar_topic}")

        self.lidar_count = sum(
            [x.msgcount for x in self.connections_lidar if x.topic == self.lidar_topic]
        )

    def __len__(self):
        return self.lidar_count

    # ------------------------- Iterators ------------------------- #
    def __iter__(self):
        iterator = self.reader.messages(
            connections=self.connections_lidar + self.connections_imu
        )

        for connection, _timestamp, rawdata in iterator:
            msg = self.reader.deserialize(rawdata, connection.msgtype)
            if connection.msgtype == "sensor_msgs/msg/PointCloud2":
                yield self._lidar_conversion(msg)
            elif connection.msgtype == "sensor_msgs/msg/Imu":
                yield self._imu_conversion(msg)
            else:
                raise ValueError(f"Unknown message type {connection.msgtype}")

    def imu_iter(self) -> Iterator[ImuMeasurement]:
        iterator = self.reader.messages(connections=self.connections_imu)

        for connection, _timestamp, rawdata in iterator:
            msg = self.reader.deserialize(rawdata, connection.msgtype)
            yield self._imu_conversion(msg)

    def lidar_iter(self) -> Iterator[LidarMeasurement]:
        iterator = self.reader.messages(connections=self.connections_lidar)

        for connection, _timestamp, rawdata in iterator:
            msg = self.reader.deserialize(rawdata, connection.msgtype)
            yield self._lidar_conversion(msg)

    # ------------------------- Convertors ------------------------- #
    def _imu_conversion(self, msg: Any) -> ImuMeasurement:
        acc = msg.linear_acceleration
        acc = np.array([acc.x, acc.y, acc.z])
        gyro = msg.angular_velocity
        gyro = np.array([gyro.x, gyro.y, gyro.z])

        stamp = Stamp(sec=msg.header.stamp.sec, nsec=msg.header.stamp.nanosec)
        return ImuMeasurement(stamp, gyro, acc)

    def _lidar_conversion(self, msg: Any) -> LidarMeasurement:
        # ------------------------- Convert to our type ------------------------- #
        fields: list[Field] = []
        for f in msg.fields:
            fields.append(
                Field(name=f.name, datatype=DataType(f.datatype), offset=f.offset)
            )

        stamp = Stamp(sec=msg.header.stamp.sec, nsec=msg.header.stamp.nanosec)

        # Adjust the stamp to the start of the scan
        # Do this early so we can use the stamp for the rest of the conversion
        match self.lidar_format.stamp:
            case LidarStamp.Start:
                pass
            case LidarStamp.End:
                stamp = stamp - self.lidar_params.delta_time()

        cloud = PointCloudMetadata(
            stamp=stamp,
            height=msg.height,
            width=msg.width,
            row_step=msg.row_step,
            point_step=msg.point_step,
            is_bigendian=msg.is_bigendian,
            is_dense=msg.is_dense,
        )
        scan: LidarMeasurement = pc2_to_evalio(cloud, fields, bytes(msg.data))  # type:ignore

        # ------------------------- Handle formatting properly ------------------------- #
        # For the ones that have been guessed, use heuristics to figure out format
        # Will only be ran on the first cloud, afterwords it will be set
        # row major
        if self.lidar_format.major == LidarMajor.Guess:
            if scan.points[0].row == scan.points[1].row:
                self.lidar_format.major = LidarMajor.Row
            else:
                self.lidar_format.major = LidarMajor.Column
        # density
        if self.lidar_format.density == LidarDensity.Guess:
            if (
                len(scan.points)
                == self.lidar_params.num_rows * self.lidar_params.num_columns
            ):
                self.lidar_format.density = LidarDensity.AllPoints
            else:
                self.lidar_format.density = LidarDensity.OnlyValidPoints
        # point stamp
        if self.lidar_format.point_stamp == LidarPointStamp.Guess:
            # Leave a little fudge room just in case
            # 2000ns = 0.002ms
            min_time = min(scan.points, key=lambda x: x.t).t
            if min_time < Duration.from_nsec(-2000):
                self.lidar_format.point_stamp = LidarPointStamp.End
            else:
                self.lidar_format.point_stamp = LidarPointStamp.Start

        if (
            self.lidar_format.major == LidarMajor.Row
            and self.lidar_format.density == LidarDensity.OnlyValidPoints
        ):
            print_warning(
                "Loading row major scan with only valid points. Can't identify where missing points should go, putting at end of scanline"
            )

        # Begin standardizing the pointcloud

        # Make point stamps relative to the start of the scan
        match self.lidar_format.point_stamp:
            case LidarPointStamp.Start:
                pass
            case LidarPointStamp.End:
                shift_point_stamps(scan, self.lidar_params.delta_time())

        # Add column indices
        if self.custom_col_func is not None:
            self.custom_col_func(scan)
        else:
            match self.lidar_format.major:
                case LidarMajor.Row:
                    fill_col_row_major(scan)
                case LidarMajor.Column:
                    fill_col_col_major(scan)

        # Reorder the points into row major with invalid points in the correct spots
        if (
            self.lidar_format.major == LidarMajor.Row
            and self.lidar_format.density == LidarDensity.AllPoints
        ):
            pass
        else:
            reorder_points(
                scan, self.lidar_params.num_rows, self.lidar_params.num_columns
            )

        return scan

__init__

__init__(
    path: Path,
    lidar_topic: str,
    imu_topic: str,
    lidar_params: LidarParams,
    type_store: Optional[Stores] = None,
    lidar_format: Optional[LidarFormatParams] = None,
    custom_col_func: Optional[
        Callable[[LidarMeasurement], None]
    ] = None,
)

Parameters:

  • path (Path) –

    Location of rosbag file(s) or dir(s). If a directory is passed containing multiple bags (ros1 or ros2), all will be loaded.

  • lidar_topic (str) –

    Name of lidar topic.

  • imu_topic (str) –

    Name of imu topic.

  • lidar_params (LidarParams) –

    Lidar parameters, can be gotten from lidar_params.

  • type_store (Optional[Stores], default: None ) –

    Additional type store to be loaded into rosbags. Defaults to None.

  • lidar_format (Optional[LidarFormatParams], default: None ) –

    Various parameters for how lidar data is stored. If not specified, most will try to be inferred. We strongly recommend setting this to ensure data is standardized properly. Defaults to None.

  • custom_col_func (Optional[Callable[[LidarMeasurement], None]], default: None ) –

    Function to put the point cloud in row major format. Will generally not be needed, except for strange default orderings. Defaults to None.

Raises:

  • FileNotFoundError

    If the path is a directory and no .bag files are found.

  • ValueError

    If the lidar or imu topic is not found in the bag file.

Source code in python/evalio/datasets/loaders.py
def __init__(
    self,
    path: Path,
    lidar_topic: str,
    imu_topic: str,
    lidar_params: LidarParams,
    type_store: Optional[Stores] = None,
    # Reduce compute by telling the iterator how to format the pointcloud
    lidar_format: Optional[LidarFormatParams] = None,
    custom_col_func: Optional[Callable[[LidarMeasurement], None]] = None,
):
    """
    Args:
        path (Path): Location of rosbag file(s) or dir(s). If a directory is passed containing multiple bags (ros1 or ros2), all will be loaded.
        lidar_topic (str): Name of lidar topic.
        imu_topic (str): Name of imu topic.
        lidar_params (LidarParams): Lidar parameters, can be gotten from [lidar_params][evalio.datasets.Dataset.lidar_params].
        type_store (Optional[Stores], optional): Additional type store to be loaded into rosbags. Defaults to None.
        lidar_format (Optional[LidarFormatParams], optional): Various parameters for how lidar data is stored. If not specified, most will try to be inferred. We strongly recommend setting this to ensure data is standardized properly. Defaults to None.
        custom_col_func (Optional[Callable[[LidarMeasurement], None]], optional): Function to put the point cloud in row major format. Will generally not be needed, except for strange default orderings. Defaults to None.

    Raises:
        FileNotFoundError: If the path is a directory and no .bag files are found.
        ValueError: If the lidar or imu topic is not found in the bag file.
    """
    self.lidar_topic = lidar_topic
    self.imu_topic = imu_topic
    self.lidar_params = lidar_params
    if lidar_format is None:
        self.lidar_format = LidarFormatParams()
    else:
        self.lidar_format = lidar_format
    self.custom_col_func = custom_col_func

    # Find all bags (may be either ros1 .bag files or ros2 bag/ dirs)
    if path.is_file():
        # Provide path is a ros1 .bag file
        self.path = [path]
    else:

        def is_ros2_bag(d: Path) -> bool:
            return bool(list(d.glob("*.mcap")) + list(d.glob("*.db3")))

        # Path provided is a directory may be ros2 bag/ dir or contain multiple bags
        ros1_bag_file_list = [p for p in path.glob("*.bag")]
        ros2_bag_dir_list = [d for d in path.glob("*/") if is_ros2_bag(d)]

        if ros1_bag_file_list:  # path contains ros1 .bag files
            self.path = ros1_bag_file_list
        elif ros2_bag_dir_list:  # path contains ros2 bag/ directories
            self.path = ros2_bag_dir_list
        elif is_ros2_bag(path):  # path is a ros2 bag/ (contains mcap or db3 file)
            self.path = [path]
        else:
            raise ValueError(
                f"Invalid rosbag path: {path}\nExpected path to be one of:\na) ros1 .bag \nb) ros2 bag/ dir or \nc) directory multiple a or b"
            )

    # Open the bag file
    self.reader = AnyReader(self.path)
    self.reader.open()

    # force load passed in type store
    # there is a default_typestore parameter in AnyReader, but it won't be used if one of bags has msgdefs
    # this works around that, but may be unstable
    # https://gitlab.com/ternaris/rosbags/-/blob/master/src/rosbags/highlevel/anyreader.py?ref_type=heads#L125-140
    if type_store is not None:
        self.reader.typestore.register(get_typestore(type_store).fielddefs)

    self.connections_lidar = [
        x for x in self.reader.connections if x.topic == self.lidar_topic
    ]
    self.connections_imu = [
        x for x in self.reader.connections if x.topic == self.imu_topic
    ]

    if len(self.connections_imu) == 0 or len(self.connections_lidar) == 0:
        table = Table(title="Rosbag Connections", highlight=True, box=box.ROUNDED)
        table.add_column("Topic", justify="right")
        table.add_column("MsgType", justify="left")
        for c in self.reader.connections:
            table.add_row(c.topic, c.msgtype)
        Console().print(table)

        if len(self.connections_imu) == 0:
            raise ValueError(f"Could not find topic {self.imu_topic}")
        if len(self.connections_lidar) == 0:
            raise ValueError(f"Could not find topic {self.lidar_topic}")

    self.lidar_count = sum(
        [x.msgcount for x in self.connections_lidar if x.topic == self.lidar_topic]
    )

BotanicGarden

Bases: Dataset

Dataset taken from a botanical garden, specifically for testing unstructured environments. Ground truth is gathered using a survey grade lidar.

Note, there is no automatic downloader for this dataset due to being uploaded on onedrive. Data can be downloaded manually and placed in the correct folder in EVALIO_DATA.

Additionally, we only include the public datasets here; more are potentially available upon request.

Source code in python/evalio/datasets/botanic_garden.py
class BotanicGarden(Dataset):
    """Dataset taken from a botanical garden, specifically for testing unstructured environments. Ground truth is gathered using a survey grade lidar.

    Note, there is no automatic downloader for this dataset due to being uploaded on onedrive. Data can be downloaded manually and placed in the correct folder in `EVALIO_DATA`.

    Additionally, we only include the public datasets here; more are potentially available upon request.
    """

    b1005_00 = auto()
    b1005_01 = auto()
    b1005_07 = auto()
    b1006_01 = auto()
    b1008_03 = auto()
    b1018_00 = auto()
    b1018_13 = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        return RosbagIter(
            self.folder / f"{self.seq_name[1:]}.bag",
            "/velodyne_points",
            "/imu/data",
            self.lidar_params(),
            lidar_format=LidarFormatParams(
                stamp=LidarStamp.End,
                point_stamp=LidarPointStamp.End,
                major=LidarMajor.Column,
                density=LidarDensity.OnlyValidPoints,
            ),
            custom_col_func=fill_col_split_row_velodyne,
        )

    def ground_truth_raw(self) -> Trajectory:
        if self.seq_name == "b1008_03":
            filename = f"{self.seq_name[1:]}_gt_output.txt"
        else:
            filename = f"{self.seq_name[1:]}_GT_output.txt"

        return Trajectory.from_csv(
            self.folder / filename,
            ["sec", "x", "y", "z", "qx", "qy", "qz", "qw"],
            delimiter=" ",
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        # https://github.com/robot-pesg/BotanicGarden/blob/main/calib/extrinsics/calib_chain.yaml
        return SE3.fromMat(
            np.array(
                [
                    [
                        0.999678872580465,
                        0.0252865664429322,
                        0.00150422292234868,
                        0.0584867781527745,
                    ],
                    [
                        -0.0252723438960774,
                        0.999649431893338,
                        -0.0078025434141585,
                        0.00840419966766332,
                    ],
                    [
                        -0.00170103929405540,
                        0.00776298237926191,
                        0.99996789371916,
                        0.168915521980526,
                    ],
                    [0.0, 0.0, 0.0, 1.0],
                ]
            )
        )

    def imu_T_gt(self) -> SE3:
        # I believe ground truth is in the lidar frame
        # https://github.com/robot-pesg/BotanicGarden/tree/main?tab=readme-ov-file#evaluation
        return self.imu_T_lidar()

    def imu_params(self) -> ImuParams:
        # Xsens Mti-680G
        # https://github.com/robot-pesg/BotanicGarden/blob/main/calib/imu_intrinsics/xsens_imu_param.yaml
        return ImuParams(
            gyro=0.0002,
            accel=0.0005,
            gyro_bias=0.0004,
            accel_bias=0.0002,
            bias_init=1e-8,
            integration=1e-8,
            gravity=np.array([0, 0, -9.81]),
            brand="Xsens",
            model="MTi-680G",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=16,
            num_columns=1825,
            min_range=0.1,
            max_range=100.0,
            brand="Velodyne",
            model="VLP-16",
        )

    def files(self) -> Sequence[str | Path]:
        out = [f"{self.seq_name[1:]}.bag", f"{self.seq_name[1:]}_GT_output.txt"]
        if self.seq_name == "b1008_03":
            out[1] = f"{self.seq_name[1:]}_gt_output.txt"

        return out

    # ------------------------- misc info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://github.com/robot-pesg/BotanicGarden"

    def environment(self) -> str:
        return "Botanic Garden"

    def vehicle(self) -> str:
        return "ATV"

    def quick_len(self) -> Optional[int]:
        return {
            "b1005_00": 5790,
            "b1005_01": 4746,
            "b1005_07": 5474,
            "b1006_01": 7445,
            "b1008_03": 6320,
            "b1018_00": 1466,
            "b1018_13": 2071,
        }[self.seq_name]

CUMulti

Bases: Dataset

Dataset collected by a ground robot (AgileX - Hunter) on the University of Colorado Boulder Campus.

Source code in python/evalio/datasets/cumulti.py
class CUMulti(Dataset):
    """
    Dataset collected by a ground robot (AgileX - Hunter) on the University of Colorado Boulder Campus.
    """

    kittredge_loop_robot1 = auto()
    kittredge_loop_robot2 = auto()
    kittredge_loop_robot3 = auto()
    kittredge_loop_robot4 = auto()
    main_campus_robot1 = auto()
    main_campus_robot2 = auto()
    main_campus_robot3 = auto()
    main_campus_robot4 = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        lidar_format = LidarFormatParams(
            stamp=LidarStamp.Start,
            point_stamp=LidarPointStamp.Start,
            major=LidarMajor.Row,
            density=LidarDensity.AllPoints,
        )

        robot_name = self.seq_name.split("_")[-1]
        return RosbagIter(
            self.folder,
            f"{robot_name}/ouster/points",
            f"{robot_name}/imu/data",
            self.lidar_params(),
            lidar_format=lidar_format,
            type_store=Stores.ROS2_FOXY,
        )

    def ground_truth_raw(self) -> Trajectory:
        # Sequence Naming information
        components = self.seq_name.split("_")
        robot_name = components[-1]
        loc_name = "_".join(components[:2])
        gt_file = self.folder / f"{loc_name}_{robot_name}_ref.csv"

        # Load the Trajectory which provides solutions in the UTM frame
        traj_utm = Trajectory.from_csv(
            gt_file, ["sec", "x", "y", "z", "qx", "qy", "qz", "qw"]
        )

        # Subtract out the initial position to get a local frame reference
        init_position = traj_utm.poses[0].trans
        return Trajectory(
            poses=[SE3(p.rot, p.trans - init_position) for p in traj_utm.poses],
            stamps=traj_utm.stamps,
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        # Supplied by CU-Multi Authors
        return SE3.fromMat(
            np.array(
                [
                    [-1.0, 0.0, 0.0, -0.058038],
                    [0.0, -1.0, 0.0, 0.015573],
                    [0.0, 0.0, 1.0, 0.049603],
                    [0.0, 0.0, 0.0, 1.000000],
                ]
            )
        )

    def imu_T_gt(self) -> SE3:
        # Groundtruth provided in the IMU Frame
        return SE3.identity()

    def imu_params(self) -> ImuParams:
        # https://www.mouser.com/datasheet/2/1083/3dmgq7_gnssins_ds_0-1900596.pdf
        return ImuParams(
            gyro=4.363323129985824e-05,  # From 0.15 Deg / sqrt(hr)
            accel=1.962e-4,  # From 20 micro-gravity / sqrt(Hz)
            gyro_bias=1e-6,  # TODO (dan)
            accel_bias=1e-6,  # TODO (dan)
            bias_init=1e-8,
            integration=1e-8,
            gravity=np.array([0, 0, -9.81]),
            brand="MicroStrain",
            model="3DM-GQ7",
        )

    def lidar_params(self) -> LidarParams:
        # Ouster OS 64 Rev 7
        return LidarParams(
            rate=20,
            num_rows=64,
            num_columns=1024,
            min_range=1.0,
            max_range=200.0,
            brand="Ouster",
            model="OS-64 (Rev 7)",
        )

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://arpg.github.io/cumulti/"

    @classmethod
    def dataset_name(cls) -> str:
        return "cumulti"

    def environment(self) -> str:
        return "CU Boulder Campus"

    def vehicle(self) -> str:
        return "ATV"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> list[str | Path]:
        components = self.seq_name.split("_")
        robot_name = components[-1]
        loc_name = "_".join(components[:2])

        return [
            self.folder / f"{robot_name}_{loc_name}_imu_gps",  # IMU Bag
            self.folder / f"{robot_name}_{loc_name}_lidar",  # LIDAR Bag
            self.folder / f"{loc_name}_{robot_name}_ref.csv",  # Reference Solution
        ]

    def download(self):
        # Sequence Naming information
        components = self.seq_name.split("_")
        robot_name = components[-1]
        loc_name = "_".join(components[:2])

        # File Download URLS
        globus_url = r"https://g-ad45ee.3d2bab.75bc.data.globus.org"
        seq_url_base_path = (
            f"{globus_url}/{loc_name}/{robot_name}/{robot_name}_{loc_name}"
        )
        lidar_url = f"{seq_url_base_path}_lidar.zip"
        imu_url = f"{seq_url_base_path}_imu_gps.zip"

        # Download destination zip files
        lidar_zip_file = self.folder / f"{robot_name}_{loc_name}_lidar.zip"
        imu_zip_file = self.folder / f"{robot_name}_{loc_name}_imu_gps.zip"

        # Download all of the data
        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        for zip_file, url in [(lidar_zip_file, lidar_url), (imu_zip_file, imu_url)]:
            if not zip_file.is_file():
                print(url)
                _urlretrieve(url, zip_file)
            else:
                print("Archive already exists. Skipping Download.")

            # Extract from the zip only what we dont already have
            print("Extracting data...")
            _extract_noreplace(zip_file, self.folder)

        # Download the groundtruth
        gt_url = f"{globus_url}/{loc_name}/{robot_name}/{loc_name}_{robot_name}/"
        gt_file = self.folder / f"{loc_name}_{robot_name}_ref.csv"
        print(gt_url)
        if not gt_file.is_file():
            _urlretrieve(gt_url, gt_file)
        else:
            print("Groundtruth already exists. Skipping Download.")

        # If we have extracted everything we need then remove the zip directory
        if self.is_downloaded():
            print("All data downloaded. Removing zip files...")
            for zip_file in [lidar_zip_file, imu_zip_file]:
                os.remove(zip_file)

EnWide

Bases: Dataset

Dataset taken in purposely degenerate locations such as a field, intersections, tunnels, and runways. All data comes directly from the Ouster unit.

Note, this dataset does not have ground truth orientation, only ground truth positional values taken from a Leica MS60 Prism.

Source code in python/evalio/datasets/enwide.py
class EnWide(Dataset):
    """Dataset taken in purposely degenerate locations such as a field, intersections, tunnels, and runways. All data comes directly from the Ouster unit.

    Note, this dataset does not have ground truth orientation, only ground truth positional values taken from a Leica MS60 Prism.
    """

    field_d = auto()
    field_s = auto()
    intersection_d = auto()
    intersection_s = auto()
    katzensee_d = auto()
    katzensee_s = auto()
    runway_d = auto()
    runway_s = auto()
    tunnel_d = auto()
    tunnel_s = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        return RosbagIter(
            self.folder,
            "/ouster/points",
            "/ouster/imu",
            self.lidar_params(),
            lidar_format=LidarFormatParams(
                stamp=LidarStamp.Start,
                point_stamp=LidarPointStamp.Start,
                major=LidarMajor.Row,
                density=LidarDensity.AllPoints,
            ),
        )

    def ground_truth_raw(self) -> Trajectory:
        return Trajectory.from_csv(
            self.folder / f"gt-{self.seq_name}.csv",
            ["sec", "x", "y", "z", "qx", "qy", "qz", "qw"],
            delimiter=" ",
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        scale = 100
        imu_T_sensor = SE3(
            SO3(qx=0.0, qy=0.0, qz=0.0, qw=1.0),
            np.array([6.253 / scale, -11.775 / scale, 7.645 / scale]),
        )
        lidar_T_sensor = SE3(
            SO3(qx=0.0, qy=0.0, qz=1.0, qw=0.0),
            np.array([0.0, 0.0, 0.3617 / scale]),
        )
        # TODO: Hardcode this later on
        return imu_T_sensor * lidar_T_sensor.inverse()

    def imu_T_gt(self) -> SE3:
        # TODO: Needs to be inverted?
        return SE3(
            SO3(qx=0.0, qy=0.0, qz=0.0, qw=1.0),
            np.array([-0.006253, 0.011775, 0.10825]),
        )

    def imu_params(self) -> ImuParams:
        # TODO: Verify these values
        return ImuParams(
            gyro=0.000261799,
            accel=0.000230,
            gyro_bias=0.0000261799,
            accel_bias=0.0000230,
            bias_init=1e-7,
            integration=1e-7,
            gravity=np.array([0, 0, 9.81]),
            brand="TDK",
            model="IAM-20680HT",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=128,
            num_columns=1024,
            min_range=0.0,
            max_range=100.0,
            brand="Ouster",
            model="OS0-128",
        )

    # ------------------------- dataset info ------------------------- #
    @classmethod
    def dataset_name(cls) -> str:
        return "enwide"

    @staticmethod
    def url() -> str:
        return "https://projects.asl.ethz.ch/datasets/enwide"

    def environment(self) -> str:
        if "tunnel" in self.seq_name:
            return "Tunnel"
        elif "runway" in self.seq_name or "intersection" in self.seq_name:
            return "Planar Road"
        else:
            return "Field"

    def vehicle(self) -> str:
        return "Handheld"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        return {
            "intersection_s": [
                "2023-08-09-16-19-09-intersection_s.bag",
                "gt-intersection_s.csv",
            ],
            "runway_s": ["2023-08-09-18-44-24-runway_s.bag", "gt-runway_s.csv"],
            "katzensee_s": [
                "2023-08-21-10-20-22-katzensee_s.bag",
                "gt-katzensee_s.csv",
            ],
            "runway_d": ["2023-08-09-18-52-05-runway_d.bag", "gt-runway_d.csv"],
            "tunnel_d": ["2023-08-08-17-50-31-tunnel_d.bag", "gt-tunnel_d.csv"],
            "field_d": ["2023-08-09-19-25-45-field_d.bag", "gt-field_d.csv"],
            "katzensee_d": [
                "2023-08-21-10-29-20-katzensee_d.bag",
                "gt-katzensee_d.csv",
            ],
            "tunnel_s": ["2023-08-08-17-12-37-tunnel_s.bag", "gt-tunnel_s.csv"],
            "intersection_d": [
                "2023-08-09-17-58-11-intersection_d.bag",
                "gt-intersection_d.csv",
            ],
            "field_s": ["2023-08-09-19-05-05-field_s.bag", "gt-field_s.csv"],
        }[self.seq_name]

    def download(self):
        bag_file, gt_file = cast(list[str], self.files())

        url = f"http://robotics.ethz.ch/~asl-datasets/2024_ICRA_ENWIDE/{self.seq_name}/"

        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        if not (self.folder / gt_file).exists():
            _urlretrieve(url + gt_file, self.folder / gt_file)
        if not (self.folder / bag_file).exists():
            _urlretrieve(url + bag_file, self.folder / bag_file)

    def quick_len(self) -> Optional[int]:
        return {
            "field_d": 1477,
            "field_s": 1671,
            "intersection_d": 1828,
            "intersection_s": 1997,
            "katzensee_d": 858,
            "katzensee_s": 1620,
            "runway_d": 1902,
            "runway_s": 2238,
            "tunnel_d": 1189,
            "tunnel_s": 2380,
        }[self.seq_name]

HeLiPR

Bases: Dataset

Self-driving car dataset taken in urban environments. Ground truth is generated using filtering of an RTK-GNSS system.

The vehicle had multiple lidar sensors mounted; we utilize the high resolution Ouster at the top of the vehicle.

Source code in python/evalio/datasets/helipr.py
class HeLiPR(Dataset):
    """Self-driving car dataset taken in urban environments. Ground truth is generated using filtering of an RTK-GNSS system.

    The vehicle had multiple lidar sensors mounted; we utilize the high resolution Ouster at the top of the vehicle.
    """

    # Had to remove a couple of them due to not having imu data
    # kaist_04 = auto()
    kaist_05 = auto()
    kaist_06 = auto()
    # dcc_04 = auto()
    dcc_05 = auto()
    dcc_06 = auto()
    # riverside_04 = auto()
    riverside_05 = auto()
    riverside_06 = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        imu_file = self.folder / "xsens_imu.csv"

        # Load in all IMU data
        imu_stamps = np.loadtxt(imu_file, usecols=0, dtype=np.int64, delimiter=",")
        imu_stamps = [Stamp.from_nsec(x) for x in imu_stamps]
        imu_data = np.loadtxt(imu_file, usecols=(11, 12, 13, 14, 15, 16), delimiter=",")
        assert len(imu_stamps) == len(imu_data)
        imu_data = [
            ImuMeasurement(stamp, gyro, acc)
            for stamp, gyro, acc in zip(imu_stamps, imu_data[:, 3:], imu_data[:, :3])
        ]

        # setup all the lidar data
        lidar_path = self.folder / "Ouster"
        lidar_files = sorted(list(lidar_path.glob("*")))
        lidar_stamps = [Stamp.from_nsec(int(x.stem)) for x in lidar_files]
        lidar_params = self.lidar_params()

        def lidar_iter():
            for stamp, file in zip(lidar_stamps, lidar_files):
                mm = helipr_bin_to_evalio(str(file), stamp, lidar_params)
                yield mm

        return RawDataIter(
            lidar_iter(),
            imu_data.__iter__(),
            len(lidar_stamps),
        )

    def ground_truth_raw(self) -> Trajectory:
        return Trajectory.from_csv(
            self.folder / "Ouster_gt.txt",
            ["nsec", "x", "y", "z", "qx", "qy", "qz", "qw"],
            delimiter=" ",
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        return SE3(
            SO3.fromMat(
                np.array(
                    [
                        [0.999715495593027, 0.0223448061210468, -0.00834490926264448],
                        [-0.0224514077723064, 0.999664614804883, -0.0129070599303583],
                        [0.00805370475188661, 0.0130907427756056, 0.999881878170293],
                    ]
                )
            ),
            np.array([-0.41696532, -0.00301141, 0.2996]),
        )

    def imu_T_gt(self) -> SE3:
        # GT is in the Ouster frame
        return self.imu_T_lidar()

    def imu_params(self) -> ImuParams:
        # Xsens MTi-300
        # https://www.xsens.com/hubfs/Downloads/Leaflets/MTi-300.pdf
        return ImuParams(
            gyro=0.000174532925199,
            accel=0.00014715,
            gyro_bias=0.000174532925199,
            accel_bias=0.00014715,
            bias_init=1e-8,
            integration=1e-8,
            gravity=np.array([0, 0, -9.81]),
            brand="Xsens",
            model="MTi-300",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=128,
            # TODO: This seems wrong... but it's what I'm getting out of the data
            num_columns=1025,
            min_range=1.0,
            max_range=200.0,
            brand="Ouster",
            model="OS2-128",
        )

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://sites.google.com/view/heliprdataset/"

    @classmethod
    def dataset_name(cls) -> str:
        return "helipr"

    def environment(self) -> str:
        return "Urban Driving"

    def vehicle(self) -> str:
        return "Car"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        return ["Ouster", "Ouster_gt.txt", "xsens_imu.csv"]

    def download(self):
        id_gt = {
            # "kaist_04": "",
            "kaist_05": "17S4649polOCfN0IOBCCxQ85UrdXf1jhF",
            "kaist_06": "1GzU4gaQKL1XPtM5t4HWw2r6EvKJOWJV_",
            # "dcc_04": "1ZG3muCWwrZrVhtOsSTUMBWdUhieBZnZy",
            "dcc_05": "1_GrcOKatx6F0DqglW0L9vk4ENBVFs0ZV",
            "dcc_06": "1Bxbl3T3OGrtn8Gh8BfeV8KJjwkgRtBMv",
            # "riverside_04": "",
            "riverside_05": "1IWj2bI7D5mPZWoh_09x0nyaM2Uf36VJM",
            "riverside_06": "1z7i2kxQV7edKmBtJ0jTjQKlShbc7MTeJ",
        }[self.seq_name]

        id_imu = {
            # "kaist_04": "",
            "kaist_05": "1R0Z7Z9BAhqOSNsD1ft6vqenH644rxXk9",
            "kaist_06": "1X-KiLi26PpJpTbZ3xupBq8I74OdXlSYU",
            # "dcc_04": "1u5eZK1sP_Jr3XasZ7PFKFGryVLuTUpGp",
            "dcc_05": "1X3_BJsVyaQZ7yL5t0stqr7j-G1K1sq5R",
            "dcc_06": "1WqxElIxpXR1uXTIRTow2mZgPFooy2BBt",
            # "riverside_04": "",
            "riverside_05": "1mqiOrq9gJLtrZn6QZdEts4yM2rGk_xfY",
            "riverside_06": "11EvRS44Eny6uwaT0RyfYRCxwvOPzSN4X",
        }[self.seq_name]

        id_lidar = {
            # "kaist_04": "",
            "kaist_05": "1FM5L17x12Lh3byp9m4h8njB-4RCP4HeZ",
            "kaist_06": "1FgNG22gYkOTaWN5mtaXmR2RHbFYJ5ufo",
            # "dcc_04": "1WcUkHU-kuH_g7GCSHJDrpkuJu_xm5Wfx",
            "dcc_05": "1YqCnquttT6WXcYyHnq4pzhgEGoEjvY4p",
            "dcc_06": "1tThqQ706gUuoV29g2l1c2vjEHbOfvKsa",
            # "riverside_04": "",
            "riverside_05": "1v1ZdYkNwlxXuFCpTug80pNdFfc5ZTWWG",
            "riverside_06": "1-ll0t8goMGb0Qb86nvkerC4quJS3mzPU",
        }[self.seq_name]

        import gdown

        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        folder_trail = f"{self.folder}{os.sep}"
        gdown.download(id=id_gt, output=folder_trail, resume=True)
        gdown.download(id=id_imu, output=folder_trail, resume=True)

        if not (self.folder / "Ouster").exists():
            gdown.download(id=id_lidar, output=folder_trail, resume=True)
            # extract the lidar data
            print("Extracting lidar data...")
            tar_file = self.folder / "Ouster.tar.gz"
            with tarfile.open(str(tar_file)) as tar:
                tar.extractall(path=self.folder)
            print("Removing tar file...")
            tar_file.unlink()

    def quick_len(self) -> Optional[int]:
        return {
            "kaist_05": 12477,
            "kaist_06": 12152,
            "dcc_05": 10810,
            "dcc_06": 10742,
            "riverside_05": 8551,
            "riverside_06": 11948,
        }[self.seq_name]

Hilti2022

Bases: Dataset

Sequences with ground truth taken from the Hilti 2022 SLAM Challenge, mostly taken from indoors.

Source code in python/evalio/datasets/hilti_2022.py
class Hilti2022(Dataset):
    """Sequences with ground truth taken from the Hilti 2022 SLAM Challenge, mostly taken from indoors."""

    construction_upper_level_1 = auto()
    construction_upper_level_2 = auto()
    construction_upper_level_3 = auto()
    basement_2 = auto()
    attic_to_upper_gallery_2 = auto()
    corridor_lower_gallery_2 = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        bag, _ = self.files()
        return RosbagIter(
            self.folder / bag,
            "/hesai/pandar",
            "/alphasense/imu",
            self.lidar_params(),
            lidar_format=LidarFormatParams(
                stamp=LidarStamp.Start,
                point_stamp=LidarPointStamp.Start,
                major=LidarMajor.Column,
                density=LidarDensity.OnlyValidPoints,
            ),
        )

    def ground_truth_raw(self) -> Trajectory:
        _, gt = self.files()
        return Trajectory.from_csv(
            self.folder / gt,
            ["sec", "x", "y", "z", "qx", "qy", "qz", "qw"],
            delimiter=" ",
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        return SE3(
            SO3(qx=0.7071068, qy=-0.7071068, qz=0.0, qw=0.0),
            np.array([-0.001, -0.00855, 0.055]),
        )

    def imu_T_gt(self) -> SE3:
        return SE3.identity()

    def imu_params(self) -> ImuParams:
        # From their kalibur config (in pdf)
        # https://tp-public-facing.s3.eu-north-1.amazonaws.com/Challenges/2022/2022322_calibration_files.zip
        # https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmi085-ds001.pdf
        return ImuParams(
            gyro=0.00019,
            accel=0.00132435,
            gyro_bias=0.000266,
            accel_bias=0.0043,
            bias_init=1e-8,
            integration=1e-8,
            gravity=np.array([0, 0, -9.81]),
            brand="Bosch",
            model="BMI085",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=32,
            num_columns=2000,
            # Increase this a smidge to remove vehicle from scan
            min_range=0.5,
            max_range=120.0,
            brand="Hesai",
            model="PandarXT-32",
        )

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://hilti-challenge.com/dataset-2022.html"

    def environment(self) -> str:
        return "Indoor"

    def vehicle(self) -> str:
        return "Handheld"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        filename = {
            "construction_upper_level_1": "exp04_construction_upper_level",
            "construction_upper_level_2": "exp05_construction_upper_level_2",
            "construction_upper_level_3": "exp06_construction_upper_level_3",
            "basement_2": "exp14_basement_2",
            "attic_to_upper_gallery_2": "exp16_attic_to_upper_gallery_2",
            "corridor_lower_gallery_2": "exp18_corridor_lower_gallery_2",
        }[self.seq_name]

        bag_file = f"{filename}.bag"
        gt_file = f"{filename}_imu.txt"

        # Extra space in these ones for some reason
        if "construction" in self.seq_name:
            gt_file = "exp_" + gt_file[3:]

        return [bag_file, gt_file]

    def download(self):
        bag_file, gt_file = cast(list[str], self.files())

        url = "https://tp-public-facing.s3.eu-north-1.amazonaws.com/Challenges/2022/"

        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        if not (self.folder / gt_file).exists():
            print(f"Downloading {gt_file}")
            _urlretrieve(url + gt_file, self.folder / gt_file)
        if not (self.folder / bag_file).exists():
            print(f"Downloading {bag_file}")
            _urlretrieve(url + bag_file, self.folder / bag_file)

    def quick_len(self) -> Optional[int]:
        return {
            "construction_upper_level_1": 1258,
            "construction_upper_level_2": 1248,
            "construction_upper_level_3": 1508,
            "basement_2": 740,
            "attic_to_upper_gallery_2": 2003,
            "corridor_lower_gallery_2": 1094,
        }[self.seq_name]

MultiCampus

Bases: Dataset

Data taken from a variety of campus (KTH, NTU, TUHH) in Asia and Europe at different seasons, at day and night, and with an ATV and handheld platform.

Ground truth was measured using a continuous optimization of lidar scans matched against a laser scanner map.

Source code in python/evalio/datasets/multi_campus.py
class MultiCampus(Dataset):
    """Data taken from a variety of campus (KTH, NTU, TUHH) in Asia and Europe at different seasons, at day and night, and with an ATV and handheld platform.

    Ground truth was measured using a continuous optimization of lidar scans matched against a laser scanner map.
    """

    ntu_day_01 = auto()
    ntu_day_02 = auto()
    ntu_day_10 = auto()
    ntu_night_04 = auto()
    ntu_night_08 = auto()
    ntu_night_13 = auto()
    kth_day_06 = auto()
    kth_day_09 = auto()
    kth_day_10 = auto()
    kth_night_01 = auto()
    kth_night_04 = auto()
    kth_night_05 = auto()
    tuhh_day_02 = auto()
    tuhh_day_03 = auto()
    tuhh_day_04 = auto()
    tuhh_night_07 = auto()
    tuhh_night_08 = auto()
    tuhh_night_09 = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        lidar_format = LidarFormatParams(
            stamp=LidarStamp.End,
            point_stamp=LidarPointStamp.Start,
            major=LidarMajor.Row,
            density=LidarDensity.AllPoints,
        )

        # The NTU sequences use the ATV platform and a VectorNav vn100 IMU
        if "ntu" in self.seq_name:
            return RosbagIter(
                self.folder,
                "/os_cloud_node/points",
                "/vn100/imu",
                self.lidar_params(),
                lidar_format=lidar_format,
            )
        # The KTH and TUHH sequences use the hand-held platform and a VectorNav vn200 IMU
        elif "kth" in self.seq_name or "tuhh" in self.seq_name:
            return RosbagIter(
                self.folder,
                "/os_cloud_node/points",
                "/vn200/imu",
                self.lidar_params(),
                lidar_format=lidar_format,
            )
        else:
            raise ValueError(f"Unknown sequence: {self.seq_name}")

    def ground_truth_raw(self) -> Trajectory:
        return Trajectory.from_csv(
            self.folder / "pose_inW.csv",
            ["num", "sec", "x", "y", "z", "qx", "qy", "qz", "qw"],
            skip_lines=1,
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        # The NTU sequences use the ATV platform
        # Taken from calib file at: https://mcdviral.github.io/Download.html#calibration
        if "ntu" in self.seq_name:
            return SE3.fromMat(
                np.array(
                    [
                        [
                            0.9999346552051229,
                            0.003477624535771754,
                            -0.010889970036688295,
                            -0.060649229060416594,
                        ],
                        [
                            0.003587143302461965,
                            -0.9999430279821171,
                            0.010053516443599904,
                            -0.012837544242408117,
                        ],
                        [
                            -0.010854387257665576,
                            -0.01009192338171122,
                            -0.999890161647627,
                            -0.020492606896077407,
                        ],
                        [0.0, 0.0, 0.0, 1.0],
                    ]
                )
            )
        # The KTH and TUHH sequences use the hand-held platform
        # Taken from calib file at: https://mcdviral.github.io/Download.html#calibration
        elif "kth" in self.seq_name or "tuhh" in self.seq_name:
            return SE3.fromMat(
                np.array(
                    [
                        [
                            0.9999135040741837,
                            -0.011166365511073898,
                            -0.006949579221822984,
                            -0.04894521120494695,
                        ],
                        [
                            -0.011356389542502144,
                            -0.9995453006865824,
                            -0.02793249526856565,
                            -0.03126929060348084,
                        ],
                        [
                            -0.006634514801117132,
                            0.02800900135032654,
                            -0.999585653686922,
                            -0.01755515794222565,
                        ],
                        [0.0, 0.0, 0.0, 1.0],
                    ]
                )
            )
        else:
            raise ValueError(f"Unknown sequence: {self.seq_name}")

    def imu_T_gt(self) -> SE3:
        return SE3.identity()

    def imu_params(self) -> ImuParams:
        # The NTU sequences use the ATV platform and a VectorNav vn100 IMU
        # The KTH and TUHH sequences use the hand-held platform and VectorNav vn200 IMU
        # Both the vn100 and vn200 have the same IMU specifications
        if "ntu" in self.seq_name:
            model = "VN-100"
        else:
            model = "VN-200"

        return ImuParams(
            gyro=0.000061087,  # VectorNav Datasheet
            accel=0.00137,  # VectorNav Datasheet
            gyro_bias=0.000061087,
            accel_bias=0.000137,
            bias_init=1e-7,
            integration=1e-7,
            gravity=np.array([0, 0, -9.81]),
            brand="VectorNav",
            model=model,
        )
        # Note- Current estimates for imu bias should be pessimistic estimates

    def lidar_params(self) -> LidarParams:
        # The NTU sequences use the ATV platform and an Ouster OS1 - 128
        if "ntu" in self.seq_name:
            return LidarParams(
                num_rows=128,
                num_columns=1024,
                min_range=0.1,
                max_range=120.0,
                brand="Ouster",
                model="OS1-128",
            )
        # The KTH and TUHH sequences use the hand-held platform and an Ouster OS1 - 64
        elif "kth" in self.seq_name or "tuhh" in self.seq_name:
            return LidarParams(
                num_rows=64,
                num_columns=1024,
                min_range=0.1,
                max_range=120.0,
                brand="Ouster",
                model="OS1-64",
            )
        else:
            raise ValueError(f"Unknown sequence: {self.seq_name}")

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://mcdviral.github.io/"

    def environment(self) -> str:
        if "ntu" in self.seq_name:
            return "NTU Campus"
        elif "kth" in self.seq_name:
            return "KTH Campus"
        elif "tuhh" in self.seq_name:
            return "TUHH Campus"
        else:
            raise ValueError(f"Unknown sequence: {self.seq_name}")

    def vehicle(self) -> str:
        if "ntu" in self.seq_name:
            return "ATV"
        elif "kth" in self.seq_name or "tuhh" in self.seq_name:
            return "Handheld"
        else:
            raise ValueError(f"Unknown sequence: {self.seq_name}")

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        if "ntu" in self.seq_name:
            beams = 128
            imu = "vn100"
        else:
            beams = 64
            imu = "vn200"

        return [
            f"{self.seq_name}_{imu}.bag",
            f"{self.seq_name}_os1_{beams}.bag",
            "pose_inW.csv",
        ]

    def download(self):
        ouster_url = {
            "ntu_day_01": "127Rk2jX4I95CEWK1AOZRD9AQRxRVlWjY",
            "ntu_day_02": "1jDS84WvHCfM_L73EptXKp-BKPIPKoE0Z",
            "ntu_day_10": "1p18Fa5SXbVcCa9BJb_Ed8Fk_NRcahkCF",
            "ntu_night_04": "1k9olfETU3f3iq_9QenzEfjTpD56bOtaV",
            "ntu_night_08": "1BbtBDwT3sLCHCOFfZWeVVWbG72mWq8x8",
            "ntu_night_13": "17Fn_HRVwSEzQqXwkw0J3NnqxekUMjnYI",
            "kth_day_06": "1DHpRSoY5ysK1h2nRwks_6Sz-QZqERiXH",
            "kth_day_09": "1mhMpwr3NDYfUWL0dVAh_kCTTTLFen31C",
            "kth_day_10": "1NbOHfVaCZkXPz28VwLrWLfITXYn25odh",
            "kth_night_01": "1mbLMoTPdhUI9u-ZOYFQJOYgrcQJb3rvN",
            "kth_night_04": "1SRMbAu1UyA4lJB4hZdmY-0mic-paGkKF",
            "kth_night_05": "1m8DYu6y5BkolXkKqC9E8Lm77TpzpyeNR",
            "tuhh_day_02": "1LErPETriJjLWhMBE5jvfpxoFujn0Z3cp",
            "tuhh_day_03": "1zTU8dnYNn1WRBGY-YkzqEiofH11vryTu",
            "tuhh_day_04": "1IFzZoEyqjboOwntyiPHTUxGcBndE2e9S",
            "tuhh_night_07": "1y1GJkaofleWVU8ZoUByGkmXkq2lwm-k-",
            "tuhh_night_08": "16t33lVBzbSxrtt0vFt-ztWAxiciONWTX",
            "tuhh_night_09": "1_FsTTQe-NKvQ-1shlYNeG0uWqngA2XzC",
        }[self.seq_name]

        imu_url = {
            "ntu_day_01": "1bBKRlzwG4v7K4mBmLAQzfwp_O6yOR0Ld",
            "ntu_day_02": "1FHsJ1Hosn_j4m5KivJrdtECdFEj3Is0G",
            "ntu_day_10": "14IydATXlqbJ0333iNY7H-bFDBBBYF-nC",
            "ntu_night_04": "1dLvaCBmac-05QtPy-ZsiU6L5gY35Z_ii",
            "ntu_night_08": "1oTUfLaQO9sUjesg6Bn3xbSZt3XgQqVRo",
            "ntu_night_13": "1lru1JVyjfzM_QmctEzMtgD6ps8ib5xYs",
            "kth_day_06": "1cf_dmcFAX9-5zxB8WcFVc3MaVNczEMqn",
            "kth_day_09": "16j2Ud99lrgkNtIlPQ_OV6caqZZc-bHA-",
            "kth_day_10": "13qyhDyrj6doa7s0cdbtF1e_Bh-erFMUv",
            "kth_night_01": "1RMfF_DYxUkP6ImwCK039-qJpzbGKw_m7",
            "kth_night_04": "10KIUpaJIID293P3um8OfWWiiQ1NArj2o",
            "kth_night_05": "1_LvH-KVfBOW4ltSo8ERLEHWRb31OoAgW",
            "tuhh_day_02": "1N3l-HskmBkta4OQVAneqnJhU29-6IeK8",
            "tuhh_day_03": "12SJQrHjFKNUMeoNuXNh7l0gd1w--B5Vl",
            "tuhh_day_04": "1EToB3VXrxmoyPtdL1bnlFgG-fcegAIOt",
            "tuhh_night_07": "1Ngy1_UXOfhjhwr-BEpG6Rsh1gi1rrMho",
            "tuhh_night_08": "1bDjyQLINKWBVOg_7Q1n1mooUfM3VifOu",
            "tuhh_night_09": "1jVQTmFX2pnYNULU5CjbOVa6hp_7zQoez",
        }[self.seq_name]

        gt_url = {
            "ntu_day_01": "1Pdj4_0SRES4v9WiyCVp8dYMcRvE8X3iH",
            "ntu_day_02": "1fB-AJx6jRwEWhJ0jVLlWkc38PpKCMTNy",
            "ntu_day_10": "11DKcJWgMFjuJlvp3Ez6bFpwtTvq42JBY",
            "ntu_night_04": "1mF-fd-NRMOpx_2jhuJeiOnxKTGYLQFsx",
            "ntu_night_08": "1vTnLttDiUdLr2mSxKyKmixFENwGWAEZU",
            "ntu_night_13": "15eHWp4sfJk4inD5u3EoFjDRxWJQ6e4Dd",
            "kth_day_06": "1ilY5Krkp9E4TtFS6WD2jrhvbIqWlxk5Z",
            "kth_day_09": "1OBfXm4GS52vWGn8cAKe_FHng91GQqg7w",
            "kth_day_10": "11cdWjQ5TXHD6cDBpTsMZbeKbBeDmKeLf",
            "kth_night_01": "1zued8z-H5Qav3W2f1Gz6YU_JnzmRdedc",
            "kth_night_04": "1G6qigMKh0aUZpbwRD0a3BdB_KI0vH0cZ",
            "kth_night_05": "1HfSMwGyzAndgO66H2mpxT3IG_SZnCExC",
            "tuhh_day_02": "1PXKc0wglgSxMBxqTGOFPQvJ4abeYHmFa",
            "tuhh_day_03": "1W53_HhhNlyf8Xc185Sd171k7RXFXln0n",
            "tuhh_day_04": "1yZJdd3EekbzoZkIH4-b7lfRa3IFSpFiO",
            "tuhh_night_07": "1QDQflr2OLCNJZ1dNUWfULICf70VhV0bt",
            "tuhh_night_08": "1bF-uj8gw7HkBXzvWXwtDNS-BBbEtuKrb",
            "tuhh_night_09": "1xr5dTBydbjIhE42hNdELklruuhxgYkld",
        }[self.seq_name]

        import gdown

        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        folder = f"{self.folder}{os.sep}"
        gdown.download(id=gt_url, output=folder, resume=True)
        gdown.download(id=ouster_url, output=folder, resume=True)
        gdown.download(id=imu_url, output=folder, resume=True)

    def quick_len(self) -> Optional[int]:
        return {
            "ntu_day_01": 6024,
            "ntu_day_02": 2288,
            "ntu_day_10": 3248,
            "ntu_night_04": 2966,
            "ntu_night_08": 4668,
            "ntu_night_13": 2338,
            "kth_day_06": 8911,
            "kth_day_09": 7670,
            "kth_day_10": 6155,
            "kth_night_01": 9690,
            "kth_night_04": 7465,
            "kth_night_05": 6653,
            "tuhh_day_02": 5004,
            "tuhh_day_03": 8395,
            "tuhh_day_04": 1879,
            "tuhh_night_07": 4446,
            "tuhh_night_08": 7091,
            "tuhh_night_09": 1849,
        }[self.seq_name]

NewerCollege2020

Bases: Dataset

Dataset taken from outdoor Oxford Campus. Ground truth is generated using ICP matching against a laser scanner.

Note, there have been some reports that the laser scanner and data were collected months apart, which may have caused some inaccuracies in the ground truth data.

There are two IMUs on the handheld device, but the realsense IMU is not time-synced with the lidar data. Therefore, we utilize the Ouster IMU data instead.

Source code in python/evalio/datasets/newer_college_2020.py
class NewerCollege2020(Dataset):
    """Dataset taken from outdoor Oxford Campus. Ground truth is generated using ICP matching against a laser scanner.

    Note, there have been some reports that the laser scanner and data were collected months apart, which may have caused some inaccuracies in the ground truth data.

    There are two IMUs on the handheld device, but the realsense IMU is not time-synced with the lidar data. Therefore, we utilize the Ouster IMU data instead.
    """

    short_experiment = auto()
    long_experiment = auto()
    quad_with_dynamics = auto()
    dynamic_spinning = auto()
    parkland_mound = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        # Use Ouster IMU as lidar IMU since the realsense IMU is not time-synced
        return RosbagIter(
            self.folder,
            "/os1_cloud_node/points",
            "/os1_cloud_node/imu",
            self.lidar_params(),
            lidar_format=LidarFormatParams(
                stamp=LidarStamp.Start,
                point_stamp=LidarPointStamp.Start,
                major=LidarMajor.Column,
                density=LidarDensity.AllPoints,
            ),
        )

    def ground_truth_raw(self) -> Trajectory:
        # For some reason bag parkland mound is different
        if self.seq_name == "parkland_mound":
            return Trajectory.from_csv(
                self.folder / "registered_poses.csv",
                ["sec", "x", "y", "z", "qx", "qy", "qz", "qw"],
                delimiter=" ",
            )

        return Trajectory.from_csv(
            self.folder / "registered_poses.csv",
            ["sec", "nsec", "x", "y", "z", "qx", "qy", "qz", "qw"],
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        return SE3(
            SO3(qx=0.0, qy=0.0, qz=1.0, qw=0.0),
            np.array(
                [0.006252999883145094, -0.011775000020861626, 0.007644999772310257]
            ),
        )

    def imu_T_gt(self) -> SE3:
        return SE3(
            SO3(qx=0.0, qy=0.0, qz=0.38268, qw=0.92388),
            np.array([0.035643, 0.089026, -0.021653]),
        )

    def imu_params(self) -> ImuParams:
        return ImuParams(
            gyro=0.000261799,
            accel=0.000230,
            gyro_bias=0.0000261799,
            accel_bias=0.0000230,
            bias_init=1e-7,
            integration=1e-7,
            gravity=np.array([0, 0, -9.81]),
            brand="TDK",
            model="ICM-20948",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=64,
            num_columns=1024,
            min_range=0.1,
            max_range=120.0,
            brand="Ouster",
            model="OS1-64",
        )

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://ori-drs.github.io/newer-college-dataset/stereo-cam/"

    def environment(self) -> str:
        return "Oxford Campus"

    def vehicle(self) -> str:
        return "Handheld"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        return {
            "dynamic_spinning": [
                "rooster_2020-07-10-09-23-18_0.bag",
            ],
            "short_experiment": [
                "rooster_2020-03-10-10-36-30_0.bag",
                "rooster_2020-03-10-10-39-18_1.bag",
                "rooster_2020-03-10-10-42-05_2.bag",
                "rooster_2020-03-10-10-44-52_3.bag",
                "rooster_2020-03-10-10-47-39_4.bag",
                "rooster_2020-03-10-10-50-26_5.bag",
                "rooster_2020-03-10-10-53-13_6.bag",
                "rooster_2020-03-10-10-56-00_7.bag",
                "rooster_2020-03-10-10-58-47_8.bag",
                "rooster_2020-03-10-11-01-34_9.bag",
            ],
            "long_experiment": [
                "rooster_2020-03-10-11-36-51_0.bag",
                "rooster_2020-03-10-11-39-38_1.bag",
                "rooster_2020-03-10-11-42-25_2.bag",
                "rooster_2020-03-10-11-45-12_3.bag",
                "rooster_2020-03-10-11-47-59_4.bag",
                "rooster_2020-03-10-11-50-46_5.bag",
                "rooster_2020-03-10-11-53-33_6.bag",
                "rooster_2020-03-10-11-56-20_7.bag",
                "rooster_2020-03-10-11-59-07_8.bag",
                "rooster_2020-03-10-12-01-54_9.bag",
                "rooster_2020-03-10-12-04-41_10.bag",
                "rooster_2020-03-10-12-07-28_11.bag",
                "rooster_2020-03-10-12-10-15_12.bag",
                "rooster_2020-03-10-12-13-02_13.bag",
                "rooster_2020-03-10-12-15-49_14.bag",
                "rooster_2020-03-10-12-18-36_15.bag",
            ],
            "quad_with_dynamics": [
                "rooster_2020-07-10-09-13-52_0.bag",
                "rooster_2020-07-10-09-16-39_1.bag",
                "rooster_2020-07-10-09-19-26_2.bag",
            ],
            "parkland_mound": [
                "rooster_2020-07-10-09-31-24_0.bag",
                "rooster_2020-07-10-09-34-11_1.bag",
                "rooster_2020-07-10-09-36-58_2.bag",
            ],
        }[self.seq_name] + ["registered_poses.csv"]

    def download(self):
        folder_id = {
            "short_experiment": "1WWtyU6bv4-JKwe-XuSeKEEEBhbgoFHRG",
            "long_experiment": "1pg3jzNF59YJX_lqVf4dcYI99TyBHcJX_",
            "quad_with_dynamics": "1ScfmWiRQ_nGy3Xj5VqRSpzkEJl5BHPQv",
            "dynamic_spinning": "1x1f_WfkQIf5AtdRhnWblhkPLur5_5ck0",
            "parkland_mound": "1PAywZT8T9TbKy_XJEgWXJkFvr5C6M1pS",
        }[self.seq_name]

        gt_url = {
            "short_experiment": "11VWvHxjitd4ijARD4dJ3WjFuZ_QbInVy",
            "long_experiment": "1fT1_MhFkCn_RWzLTzo4i-sjoKa_TbIUW",
            "quad_with_dynamics": "1Cc7fiYUCtNL8qnvA0x-m4uQvRWQLdrWO",
            "dynamic_spinning": "16lLgl2iqVs5qSz-N3OZv9bZWBbvAXyP3",
            "parkland_mound": "1CMcmw9pAT1Mm-Zh-nS87i015CO-xFHwl",
        }[self.seq_name]

        import gdown

        print(f"Downloading to {self.folder}...")

        self.folder.mkdir(parents=True, exist_ok=True)
        gdown.download(id=gt_url, output=f"{self.folder}{os.sep}", resume=True)
        gdown.download_folder(id=folder_id, output=str(self.folder), resume=True)

    def quick_len(self) -> Optional[int]:
        # TODO: Missing some values here
        return {
            "short_experiment": 15302,
            "long_experiment": 26560,
        }.get(self.seq_name)

NewerCollege2021

Bases: Dataset

Dataset outdoors on oxford campus with a handheld device consisting of an alphasense core and a Ouster lidar. Ground truth is captured ICP matching against a laser scanner map.

Note there are two IMUs present; we utilize the Ouster IMU (ICM-20948)) instead of the alphasense one (Bosch BMI085). We expect the Ouster IMU to have more accurate extrinsics and the specs between the two IMUs are fairly similar.

Source code in python/evalio/datasets/newer_college_2021.py
class NewerCollege2021(Dataset):
    """Dataset outdoors on oxford campus with a handheld device consisting of an alphasense core and a Ouster lidar.
    Ground truth is captured ICP matching against a laser scanner map.

    Note there are two IMUs present; we utilize the Ouster IMU (ICM-20948)) instead of the alphasense one (Bosch BMI085).
    We expect the Ouster IMU to have more accurate extrinsics and the specs between the two IMUs are fairly similar.
    """

    quad_easy = auto()
    quad_medium = auto()
    quad_hard = auto()
    stairs = auto()
    cloister = auto()
    park = auto()
    maths_easy = auto()
    maths_medium = auto()
    maths_hard = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        return RosbagIter(
            self.folder,
            "/os_cloud_node/points",
            "/os_cloud_node/imu",
            self.lidar_params(),
            lidar_format=LidarFormatParams(
                stamp=LidarStamp.Start,
                point_stamp=LidarPointStamp.Start,
                major=LidarMajor.Row,
                density=LidarDensity.AllPoints,
            ),
        )

    def ground_truth_raw(self) -> Trajectory:
        gt_file = self.files()[-1]
        return Trajectory.from_csv(
            self.folder / gt_file,
            ["sec", "nsec", "x", "y", "z", "qx", "qy", "qz", "qw"],
        )

    # ------------------------- For loading params ------------------------- #
    def imu_T_lidar(self) -> SE3:
        return SE3(
            SO3(qx=0.0032925, qy=-0.004627, qz=-0.0024302, qw=0.99998),
            np.array([0.013801, -0.012207, -0.01514]),
        )

    def imu_T_gt(self) -> SE3:
        return SE3(
            SO3(qx=0.0032925, qy=-0.004627, qz=-0.0024302, qw=0.99998),
            np.array([0.013642, -0.011607, -0.10583]),
        )

    def imu_params(self) -> ImuParams:
        # ICM-20948
        # https://invensense.tdk.com/wp-content/uploads/2024/03/DS-000189-ICM-20948-v1.6.pdf
        return ImuParams(
            gyro=0.000261799387799,
            accel=0.0022563,
            gyro_bias=0.0000261799387799,
            accel_bias=0.00022563,
            bias_init=1e-8,
            integration=1e-8,
            gravity=np.array([0, 0, -9.81]),
            brand="TDK",
            model="ICM-20948",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=128,
            num_columns=1024,
            min_range=0.1,
            max_range=50.0,
            brand="Ouster",
            model="OS1-128",
        )

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://ori-drs.github.io/newer-college-dataset/multi-cam/"

    def environment(self) -> str:
        return "Oxford Campus"

    def vehicle(self) -> str:
        return "Handheld"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        # parse ground truth file
        if "maths" in self.seq_name:
            difficulty = self.seq_name.split("_")[1]
            gt_file = f"gt_state_{difficulty}.csv"
        else:
            name = self.seq_name.replace("_", "-")
            gt_file = f"gt-nc-{name}.csv"

        return {
            "cloister": [
                "2021-12-02-10-15-59_0-cloister.bag",
                "2021-12-02-10-19-05_1-cloister.bag",
            ],
            "maths_medium": [
                "2021-04-07-13-55-18-math-medium.bag",
            ],
            "quad_medium": [
                "2021-07-01-11-31-35_0-quad-medium.bag",
            ],
            "maths_hard": [
                "2021-04-07-13-58-54_0-math-hard.bag",
                "2021-04-07-14-02-18_1-math-hard.bag",
            ],
            "quad_hard": [
                "2021-07-01-11-35-14_0-quad-hard.bag",
            ],
            "quad_easy": [
                "2021-07-01-10-37-38-quad-easy.bag",
            ],
            "park": [
                "2021-11-30-17-09-49_0-park.bag",
                "2021-11-30-17-13-13_1-park.bag",
                "2021-11-30-17-16-38_2-park.bag",
                "2021-11-30-17-20-07_3-park.bag",
                "2021-11-30-17-23-25_4-park.bag",
                "2021-11-30-17-26-36_5-park.bag",
                "2021-11-30-17-30-06_6-park.bag",
                "2021-11-30-17-33-19_7-park.bag",
            ],
            "maths_easy": [
                "2021-04-07-13-49-03_0-math-easy.bag",
                "2021-04-07-13-52-31_1-math-easy.bag",
            ],
            "stairs": [
                "2021-07-01-10-40-50_0-stairs.bag",
            ],
        }[self.seq_name] + [gt_file]

    def download(self):
        bag_ids = {
            "quad_easy": ["1hF2h83E1THbFAvs7wpR6ORmrscIHxKMo"],
            "quad_medium": ["11bZfJce1MCM4G9YUTCyUifM715N7FSbO"],
            "quad_hard": ["1ss6KPSTZ4CRS7uHAMgqnd4GQ6tKEEiZD"],
            "stairs": ["1ql0C8el5PJs6O0x4xouqaW9n2RZy53q9"],
            "cloister": [
                "1zzX_ZrMkVOtpSoD2jQg6Gdrtv8-UjYbF",
                "1QNFQSb81gG1_jX338vO7RQkScKGT_hf1",
            ],
            "park": [
                "1KZo-gPVQTMJ4hRaiaqV3hfuVNaONScDp",
                "1eGVPwFSaG0M2M7Lci6IBjKQrEf1uqtVn",
                "1nhuoH0OcLbovbXkq3eW6whk6TIKk2SEu",
                "1pXBE1iD9iivFFliFFNs7uvWi1zjo1S0s",
                "1_eZ5i2CGL7fNHeowRd1P_sllX1nxGwGL",
                "1wMCZVbB7eaSuz6u3ObSTdGbgbRFyRQ7m",
                "10o1oR7guReYKiVk3nBiPrFWp1MnERTiH",
                "1VpLV_WUJqr770NBjF-O-DrXb5dhXRWyM",
            ],
            "maths_easy": [
                "1wRnRSni9bcBRauJEJ80sxHIaJaonrC3C",
                "1ORkYwGpQNvD48WRXICDDecbweg8MxYA8",
            ],
            "maths_medium": ["1IOq2e8Nfx79YFauBHCgdBSW9Ur5710GD"],
            "maths_hard": [
                "1qD147UWPo30B9lK3gABggCOxSAU6Pop2",
                "1_Mps_pCeUz3ZOc53lj6Hy_zDeJfPAqy8",
            ],
        }[self.seq_name]

        gt_ids = {
            "quad_easy": "1BdQiOhb_NW7VqjNtbbRAjI0JH56uKFI-",
            "quad_medium": "18aHhzTcVzXsppmk2WpiZnJhzOfREUwYP",
            "quad_hard": "1KMAG65pH8PsHUld-hTkFK4-SIIBqT5yP",
            "stairs": "17q_NYxn1SLBmUq20jgljO8HSlFF9LjDs",
            "cloister": "15I8qquSPWlySuY5_4ZBa_wL4UC7c-rQ7",
            "park": "1AkJ7lm5x2WdS3aGhKwe1PnUn6w0rbUjf",
            "maths_easy": "1dq1PqMODQBb4Hkn82h2Txgf5ZygS5udp",
            "maths_medium": "1H1U3aXv2AJQ_dexTnjaHIfzYfx8xVXpS",
            "maths_hard": "1Rb2TBKP7ISC2XzDGU68ix5lFjEB6jXeX",
        }[self.seq_name]

        import gdown

        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        gdown.download(id=gt_ids, output=f"{self.folder}{os.sep}", resume=True)
        for bid in bag_ids:
            gdown.download(id=bid, output=f"{self.folder}{os.sep}", resume=True)

    def quick_len(self) -> Optional[int]:
        return {
            "quad_easy": 1991,
            "quad_medium": 1910,
            "quad_hard": 1880,
            "stairs": 1190,
            "cloister": 2788,
            "park": 15722,
            "maths_easy": 2160,
            "maths_medium": 1770,
            "maths_hard": 2440,
        }[self.seq_name]

OxfordSpires

Bases: Dataset

Dataset taken both indoors and outdoors on the Oxford campus.

Note, we skip over a number of trajectories due to missing ground truth data.

Additionally, some of the ground truth has poses within a few milliseconds of each other - we skip over any ground truth values within 10 milliseconds of each other.

Source code in python/evalio/datasets/oxford_spires.py
class OxfordSpires(Dataset):
    """Dataset taken both indoors and outdoors on the Oxford campus.

    Note, we skip over a number of trajectories due to [missing ground truth data](https://docs.google.com/document/d/1RS9QSOP4rC7BWoCD6EYUCm9uV_oMkfa3b61krn9OLG8/edit?tab=t.0).

    Additionally, some of the ground truth has poses within a few milliseconds of each other - we skip over any ground truth values within 10 milliseconds of each other.
    """

    blenheim_palace_01 = auto()
    blenheim_palace_02 = auto()
    blenheim_palace_05 = auto()
    bodleian_library_02 = auto()
    christ_church_01 = auto()
    christ_church_02 = auto()
    christ_church_03 = auto()
    christ_church_05 = auto()
    keble_college_02 = auto()
    keble_college_03 = auto()
    keble_college_04 = auto()
    observatory_quarter_01 = auto()
    observatory_quarter_02 = auto()

    # ------------------------- For loading data ------------------------- #
    def data_iter(self) -> DatasetIterator:
        return RosbagIter(
            self.folder,
            "/hesai/pandar",
            "/alphasense_driver_ros/imu",
            self.lidar_params(),
            lidar_format=LidarFormatParams(
                stamp=LidarStamp.Start,
                point_stamp=LidarPointStamp.Start,
                major=LidarMajor.Column,
                density=LidarDensity.OnlyValidPoints,
            ),
        )

    def ground_truth_raw(self) -> Trajectory:
        # Some of these are within a few milliseconds of each other
        # skip over ones that are too close
        traj = Trajectory.from_csv(
            self.folder / "gt-tum.txt",
            ["sec", "x", "y", "z", "qx", "qy", "qz", "qw"],
            delimiter=" ",
        )

        poses: list[SE3] = []
        stamps: list[Stamp] = []
        for i in range(1, len(traj)):
            if traj.stamps[i] - traj.stamps[i - 1] > Duration.from_sec(1e-2):
                poses.append(traj.poses[i])
                stamps.append(traj.stamps[i])

        return Trajectory(metadata=traj.metadata, stamps=stamps, poses=poses)

    # ------------------------- For loading params ------------------------- #
    def cam_T_lidar(self) -> SE3:
        r = SO3(
            qx=0.5023769275907106,
            qy=0.49990425097844265,
            qz=-0.49648618825384844,
            qw=0.5012131556048427,
        )
        t = np.array([0.003242860366163889, -0.07368532755947366, -0.05485800045216396])
        return SE3(r, t)

    def cam_T_imu(self) -> SE3:
        r = SO3(
            qx=-0.003150684959962717,
            qy=0.7095105504964175,
            qz=-0.7046875827967661,
            qw=0.0005124164367280889,
        )
        t = np.array(
            [-0.005000230026155717, -0.0031440163748744266, -0.07336562959794378]
        )
        return SE3(r, t)

    def imu_T_lidar(self) -> SE3:
        return self.cam_T_imu().inverse() * self.cam_T_lidar()

    def imu_T_gt(self) -> SE3:
        # Ground truth was found in the lidar frame, but is reported in the "base frame"
        # We go back to the lidar frame (as this transform should be what they used as well)
        # then use calibration to go to imu frame
        # https://github.com/ori-drs/oxford_spires_dataset/blob/main/config/sensor.yaml
        gt_T_lidar = SE3(
            SO3(qx=0.0, qy=0.0, qz=1.0, qw=0.0), np.array([0.0, 0.0, 0.124])
        )
        return self.imu_T_lidar() * gt_T_lidar.inverse()

    def imu_params(self) -> ImuParams:
        # Same one as hilti
        # From their kalibur config (in pdf)
        # https://tp-public-facing.s3.eu-north-1.amazonaws.com/Challenges/2022/2022322_calibration_files.zip
        # https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmi085-ds001.pdf
        return ImuParams(
            gyro=0.00019,
            accel=0.00132435,
            gyro_bias=0.000266,
            accel_bias=0.0043,
            bias_init=1e-8,
            integration=1e-8,
            gravity=np.array([0, 0, -9.81]),
            brand="Bosch",
            model="BMI085",
        )

    def lidar_params(self) -> LidarParams:
        return LidarParams(
            num_rows=64,
            num_columns=1200,
            min_range=1.0,
            max_range=60.0,
            brand="Hesai",
            model="QT-64",
        )

    # ------------------------- dataset info ------------------------- #
    @staticmethod
    def url() -> str:
        return "https://dynamic.robots.ox.ac.uk/datasets/oxford-spires/"

    def environment(self) -> str:
        if "observatory" in self.seq_name or "bodleian" in self.seq_name:
            return "Oxford Campus"
        else:
            return "Indoor & Oxford Campus"

    def vehicle(self) -> str:
        return "Backpack"

    # ------------------------- For downloading ------------------------- #
    def files(self) -> Sequence[str | Path]:
        return {
            "christ_church_02": [
                "1710754066_2024-03-18-09-27-47_0",
                "1710754066_2024-03-18-09-36-49_1",
                "gt-tum.txt",
            ],
            "blenheim_palace_01": [
                "1710406700_2024-03-14-08-58-21_0_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "christ_church_05": [
                "1710926317_2024-03-20-09-18-38_0_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "keble_college_03": [
                "1710256011_2024-03-12-15-06-52_0_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "christ_church_01": [
                "1710752531_2024-03-18-09-02-12_0",
                "1710752531_2024-03-18-09-11-55_1",
                "gt-tum.txt",
            ],
            "bodleian_library_02": [
                "1716183690_2024-05-20-06-41-31_0_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "blenheim_palace_02": [
                "1710407340_2024-03-14-09-09-01_0_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "keble_college_04": [
                "1710256650_2024-03-12-15-17-31_0",
                "1710256650_2024-03-12-15-26-05_1",
                "gt-tum.txt",
            ],
            "observatory_quarter_01": [
                "1710338090_2024-03-13-13-54-51_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "christ_church_03": [
                "1710755015_2024-03-18-09-43-36_0_blurred_filtered.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "blenheim_palace_05": [
                "1710410169_2024-03-14-09-56-09_0_blurred_filtered.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "observatory_quarter_02": [
                "1710338490_2024-03-13-14-01-30_blurred_filtered.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
            "keble_college_02": [
                "1710255615_2024-03-12-15-00-16_0_blurred_filtered_compressed.db3",
                "gt-tum.txt",
                "metadata.yaml",
            ],
        }[self.seq_name]

    def download(self):
        folder_id = {
            "blenheim_palace_01": "1sQZhbdWZqyR0fLStesW2sJYuvIW9xyCD",
            "blenheim_palace_02": "1vaU7pn0cxbrBbJk1XKr9hOeeF7Zv00K9",
            "blenheim_palace_05": "1CZpiSX84g4391D-87E6AMlZI4ky1TG7p",
            "bodleian_library_02": "1koKUZrZ3dPazy2qwguPeFqla04V7-opp",
            # This one is split into two... figure out how to handle
            "christ_church_01": "1yd9jl1o4AEacKaYXCHV-AzV-FZTfRm6r",
            # This one is split into two... figure out how to handle
            "christ_church_02": "1f41VoG6mMAvpLxKciqGLhtOuj5iUK_3r",
            "christ_church_03": "14YTkMnxEWnE-iyrk30iu0I39QG-smREF",
            "christ_church_05": "1EDyyuFJ-KnLUv-S5IFv7OInNwPEFSHwl",
            "keble_college_02": "1qAocPo1_h8B2u-LdQoD2td49RJlD-1IW",
            "keble_college_03": "1u-QIvxQvjRXtt0k3vXYdB59XZQ61Khj9",
            # This one is split into two... figure out how to handle
            "keble_college_04": "1VJB8oIAoVVIhGCnbXKYz_uHfiNkwn9_i",
            "observatory_quarter_01": "1Wys3blrdfPVn-EFsXn_a0_0ngvzgSiFb",
            "observatory_quarter_02": "109uXFhqzYhn2bHv_37aQF7xPrJhOOu-_",
        }[self.seq_name]

        gt_url = {
            "blenheim_palace_01": "16et7vJhZ15yOCNYYU-i8HVOXemJM3puz",
            "blenheim_palace_02": "191MBEJuABCbb14LJhnJuvq4_ULqqbeQU",
            "blenheim_palace_05": "1jWYpiX4eUz1By1XN1g22ktzb-BCMyE7q",
            "bodleian_library_02": "1_EP7H_uO0XNhIKaFXB4nro8ymhpWB2qg",
            "christ_church_01": "1qXlfhf_0Jr6daeM3v9qmmhC-5yEI6TB5",
            "christ_church_02": "19vyhMivn4I1u-ZkLlIpoa7Nc3sdWNOU1",
            "christ_church_03": "13LbReIW7mJd6jMVBI6IcSRPWvpG6WP9c",
            "christ_church_05": "1Nxbjmwudu2b02Z2zWkJYO1I9rDPLe2Uf",
            "keble_college_02": "1hgNbsqIx8L0vM4rnPSX155sxxiIsDnJC",
            "keble_college_03": "1ybkRnb-wu4VMEqa37RUAHbUv2i-4UluB",
            "keble_college_04": "1iaGvgpDN-3CrwPPZzQjwAveXQOyQnAU4",
            "observatory_quarter_01": "1IOqvzepLesYecizYJh6JU0lJZu2WeW68",
            "observatory_quarter_02": "1iPQQD2zijlCf8a6J8YW5QBlVE2KsYRdZ",
        }[self.seq_name]

        import gdown

        print(f"Downloading to {self.folder}...")
        self.folder.mkdir(parents=True, exist_ok=True)
        gdown.download(id=gt_url, output=f"{self.folder}{os.sep}", resume=True)
        gdown.download_folder(id=folder_id, output=str(self.folder), resume=True)

    def quick_len(self) -> Optional[int]:
        # TODO: Missing some of the sequences here, need to figure out multi-folder mcap files
        return {
            "blenheim_palace_01": 4052,
            "blenheim_palace_02": 3674,
            "blenheim_palace_05": 3401,
            "bodleian_library_02": 5007,
            "christ_church_03": 3123,
            "christ_church_05": 8007,
            "keble_college_02": 3007,
            "keble_college_03": 2867,
            "observatory_quarter_01": 2894,
            "observatory_quarter_02": 2755,
        }.get(self.seq_name)

DatasetNotFound

Bases: CustomException

Exception raised when a dataset is not found.

Source code in python/evalio/datasets/parser.py
class DatasetNotFound(CustomException):
    """Exception raised when a dataset is not found."""

    def __init__(self, name: str):
        super().__init__(f"Dataset '{name}' not found")
        self.name = name

SequenceNotFound

Bases: CustomException

Exception raised when a sequence is not found.

Source code in python/evalio/datasets/parser.py
class SequenceNotFound(CustomException):
    """Exception raised when a sequence is not found."""

    def __init__(self, name: str):
        super().__init__(f"Sequence '{name}' not found")
        self.name = name

get_data_dir

get_data_dir() -> Path

Get the global data directory. This is where downloaded data is stored.

Returns:

  • Path

    Directory where datasets are stored.

Source code in python/evalio/datasets/base.py
def get_data_dir() -> Path:
    """Get the global data directory. This is where downloaded data is stored.

    Returns:
        Directory where datasets are stored.
    """
    global _DATA_DIR
    return _DATA_DIR

set_data_dir

set_data_dir(directory: Path)

Set the global location where datasets are stored. This will be used to store the downloaded data.

Parameters:

  • directory (Path) –

    Directory

Source code in python/evalio/datasets/base.py
def set_data_dir(directory: Path):
    """Set the global location where datasets are stored. This will be used to store the downloaded data.

    Args:
        directory (Path): Directory
    """
    global _DATA_DIR, _WARNED
    _DATA_DIR = directory
    _WARNED = True

all_datasets

all_datasets() -> dict[str, type[Dataset]]

Get all registered datasets.

Returns:

  • dict[str, type[Dataset]]

    A dictionary mapping dataset names to their classes.

Source code in python/evalio/datasets/parser.py
def all_datasets() -> dict[str, type[Dataset]]:
    """Get all registered datasets.

    Returns:
        A dictionary mapping dataset names to their classes.
    """
    global _DATASETS
    return {d.dataset_name(): d for d in _DATASETS}

get_dataset

get_dataset(name: str) -> type[Dataset] | DatasetNotFound

Get a registered dataset by name.

Parameters:

  • name (str) –

    The name of the dataset to retrieve.

Returns:

Source code in python/evalio/datasets/parser.py
def get_dataset(name: str) -> type[Dataset] | DatasetNotFound:
    """Get a registered dataset by name.

    Args:
        name (str): The name of the dataset to retrieve.

    Returns:
        The dataset class if found, or a DatasetNotFound error.
    """
    return all_datasets().get(name, DatasetNotFound(name))

all_sequences

all_sequences() -> dict[str, Dataset]

Get all sequences from all registered datasets.

Returns:

  • dict[str, Dataset]

    A dictionary mapping sequence names to their dataset classes.

Source code in python/evalio/datasets/parser.py
def all_sequences() -> dict[str, Dataset]:
    """Get all sequences from all registered datasets.

    Returns:
        A dictionary mapping sequence names to their dataset classes.
    """
    return {
        seq.full_name: seq for d in all_datasets().values() for seq in d.sequences()
    }

get_sequence

get_sequence(name: str) -> Dataset | SequenceNotFound

Get a registered sequence by name.

Parameters:

  • name (str) –

    The name of the sequence to retrieve.

Returns:

Source code in python/evalio/datasets/parser.py
def get_sequence(name: str) -> Dataset | SequenceNotFound:
    """Get a registered sequence by name.

    Args:
        name (str): The name of the sequence to retrieve.

    Returns:
        The dataset object if found, or a SequenceNotFound error.
    """
    return all_sequences().get(name, SequenceNotFound(name))

register_dataset

register_dataset(
    dataset: Optional[type[Dataset]] = None,
    module: Optional[ModuleType | str] = None,
) -> int | ImportError

Register a dataset.

Parameters:

  • dataset (Optional[type[Dataset]], default: None ) –

    The dataset class to register. Defaults to None.

  • module (Optional[ModuleType | str], default: None ) –

    The module containing datasets to register. Defaults to None.

Returns:

  • int | ImportError

    The number of datasets registered or an ImportError.

Source code in python/evalio/datasets/parser.py
def register_dataset(
    dataset: Optional[type[Dataset]] = None,
    module: Optional[ModuleType | str] = None,
) -> int | ImportError:
    """Register a dataset.

    Args:
        dataset (Optional[type[Dataset]], optional): The dataset class to register. Defaults to None.
        module (Optional[ModuleType  |  str], optional): The module containing datasets to register. Defaults to None.

    Returns:
        The number of datasets registered or an ImportError.
    """
    global _DATASETS

    total = 0
    if module is not None:
        if isinstance(module, str):
            try:
                module = importlib.import_module(module)
            except ImportError as e:
                return e

        new_ds = _search_module(module)
        _DATASETS.update(new_ds)
        total += len(new_ds)

    if dataset is not None and _is_dataset(dataset):
        _DATASETS.add(dataset)
        total += 1

    return total