Skip to content

dataclass

SemanticLabel

A dataclass to represent semantic labels.

Attributes:

Name Type Description
name str

Label name.

attributes list[str]

List of attribute names.

Source code in t4_devkit/dataclass/label.py
@define(frozen=True, eq=False)
class SemanticLabel:
    """A dataclass to represent semantic labels.

    Attributes:
        name (str): Label name.
        attributes (list[str], optional): List of attribute names.
    """

    name: str = field(validator=validators.instance_of(str))
    attributes: list[str] = field(
        factory=list,
        validator=validators.deep_iterable(validators.instance_of(str)),
    )

    def __eq__(self, other: str | SemanticLabel) -> bool:
        return self.name == other if isinstance(other, str) else self.name == other.name

Box2D

A class to represent 2D box.

Attributes:

Name Type Description
unix_time int

Unix timestamp.

frame_id str

Coordinates frame ID where the box is with respect to.

semantic_label SemanticLabel

SemanticLabel object.

confidence float

Confidence score of the box.

uuid str | None

Unique box identifier.

roi Roi | None

Roi object.

position Vector3 | None

3D position (x, y, z).

Examples:

>>> # without 3D position
>>> box2d = Box2D(
...     unix_time=100,
...     frame_id="camera",
...     semantic_label=SemanticLabel("car"),
...     roi=(100, 100, 50, 50),
...     confidence=1.0,
...     uuid="car2d_0",
... )
>>> # with 3D position
>>> box2d = box2d.with_position(position=(1.0, 1.0, 1.0))
Source code in t4_devkit/dataclass/box.py
@define(eq=False)
class Box2D(BaseBox):
    """A class to represent 2D box.

    Attributes:
        unix_time (int): Unix timestamp.
        frame_id (str): Coordinates frame ID where the box is with respect to.
        semantic_label (SemanticLabel): `SemanticLabel` object.
        confidence (float, optional): Confidence score of the box.
        uuid (str | None, optional): Unique box identifier.
        roi (Roi | None, optional): `Roi` object.
        position (Vector3 | None, optional): 3D position (x, y, z).

    Examples:
        >>> # without 3D position
        >>> box2d = Box2D(
        ...     unix_time=100,
        ...     frame_id="camera",
        ...     semantic_label=SemanticLabel("car"),
        ...     roi=(100, 100, 50, 50),
        ...     confidence=1.0,
        ...     uuid="car2d_0",
        ... )
        >>> # with 3D position
        >>> box2d = box2d.with_position(position=(1.0, 1.0, 1.0))
    """

    roi: Roi | None = field(
        default=None,
        converter=lambda x: None if x is None else Roi(x),
    )

    # additional attributes: set by `with_**`
    position: Vector3 | None = field(
        default=None,
        converter=lambda x: None if x is None else Vector3(x),
    )

    def with_position(self, position: Vector3Like) -> Self:
        """Return a self instance setting `position` attribute.

        Args:
            position (Vector3Like): 3D position.

        Returns:
            Self instance after setting `position`.
        """
        self.position = Vector3(position)
        return self

    def __eq__(self, other: Box2D | None) -> bool:
        if other is None:
            return False
        else:
            # NOTE: This comparison might be not enough
            eq = True
            eq &= self.unix_time == other.unix_time
            eq &= self.semantic_label == other.semantic_label
            return eq

    @property
    def offset(self) -> tuple[ScalarLike, ScalarLike] | None:
        return None if self.roi is None else self.roi.offset

    @property
    def size(self) -> tuple[ScalarLike, ScalarLike] | None:
        return None if self.roi is None else self.roi.size

    @property
    def width(self) -> ScalarLike | None:
        return None if self.roi is None else self.roi.width

    @property
    def height(self) -> ScalarLike | None:
        return None if self.roi is None else self.roi.height

    @property
    def center(self) -> tuple[ScalarLike, ScalarLike] | None:
        return None if self.roi is None else self.roi.center

    @property
    def area(self) -> ScalarLike | None:
        return None if self.roi is None else self.roi.area

with_position(position)

Return a self instance setting position attribute.

Parameters:

Name Type Description Default
position Vector3Like

3D position.

required

Returns:

Type Description
Self

Self instance after setting position.

Source code in t4_devkit/dataclass/box.py
def with_position(self, position: Vector3Like) -> Self:
    """Return a self instance setting `position` attribute.

    Args:
        position (Vector3Like): 3D position.

    Returns:
        Self instance after setting `position`.
    """
    self.position = Vector3(position)
    return self

Box3D

A class to represent 3D box.

Attributes:

Name Type Description
unix_time int

Unix timestamp.

frame_id str

Coordinates frame ID where the box is with respect to.

semantic_label SemanticLabel

SemanticLabel object.

confidence float

Confidence score of the box.

uuid str | None

Unique box identifier.

position Vector3

Box center position (x, y, z).

rotation Quaternion

Box rotation quaternion.

shape Shape

Shape object.

velocity Vector3 | None

Box velocity (vx, vy, vz).

num_points int | None

The number of points inside the box.

visibility VisibilityLevel

Box visibility.

future Future | None

Box trajectory in the future of each mode.

Examples:

>>> # without future
>>> box3d = Box3D(
...     unix_time=100,
...     frame_id="base_link",
...     semantic_label=SemanticLabel("car"),
...     position=(1.0, 1.0, 1.0),
...     rotation=(0.0, 0.0, 0.0, 1.0),
...     shape=Shape(shape_type=ShapeType.BOUNDING_BOX, size=(1.0, 1.0, 1.0)),
...     velocity=(1.0, 1.0, 1.0),
...     confidence=1.0,
...     uuid="car3d_0",
... )
>>> # with future
>>> box3d = box3d.with_future(
...     waypoints=[[[1.0, 1.0, 1.0], [2.0, 2.0, 2.0], [3.0, 3.0, 3.0]]],
...     confidences=[1.0],
... )
Source code in t4_devkit/dataclass/box.py
@define(eq=False)
class Box3D(BaseBox):
    """A class to represent 3D box.

    Attributes:
        unix_time (int): Unix timestamp.
        frame_id (str): Coordinates frame ID where the box is with respect to.
        semantic_label (SemanticLabel): `SemanticLabel` object.
        confidence (float, optional): Confidence score of the box.
        uuid (str | None, optional): Unique box identifier.
        position (Vector3): Box center position (x, y, z).
        rotation (Quaternion): Box rotation quaternion.
        shape (Shape): `Shape` object.
        velocity (Vector3 | None, optional): Box velocity (vx, vy, vz).
        num_points (int | None, optional): The number of points inside the box.
        visibility (VisibilityLevel, optional): Box visibility.
        future (Future | None, optional): Box trajectory in the future of each mode.

    Examples:
        >>> # without future
        >>> box3d = Box3D(
        ...     unix_time=100,
        ...     frame_id="base_link",
        ...     semantic_label=SemanticLabel("car"),
        ...     position=(1.0, 1.0, 1.0),
        ...     rotation=(0.0, 0.0, 0.0, 1.0),
        ...     shape=Shape(shape_type=ShapeType.BOUNDING_BOX, size=(1.0, 1.0, 1.0)),
        ...     velocity=(1.0, 1.0, 1.0),
        ...     confidence=1.0,
        ...     uuid="car3d_0",
        ... )
        >>> # with future
        >>> box3d = box3d.with_future(
        ...     waypoints=[[[1.0, 1.0, 1.0], [2.0, 2.0, 2.0], [3.0, 3.0, 3.0]]],
        ...     confidences=[1.0],
        ... )
    """

    position: Vector3 = field(converter=Vector3)
    rotation: Quaternion = field(converter=to_quaternion)
    shape: Shape = field(validator=validators.instance_of(Shape))
    velocity: Vector3 | None = field(default=None, converter=converters.optional(Vector3))
    num_points: int | None = field(
        default=None,
        validator=validators.optional((validators.instance_of(int), validators.ge(0))),
    )
    visibility: VisibilityLevel = field(
        default=VisibilityLevel.UNAVAILABLE,
        converter=VisibilityLevel,
        validator=validators.instance_of(VisibilityLevel),
    )

    # additional attributes: set by `with_**`
    future: Future | None = field(
        default=None,
        validator=validators.optional(validators.instance_of(Future)),
    )

    def with_future(
        self,
        timestamps: ArrayLike,
        confidences: ArrayLike,
        waypoints: ArrayLike,
    ) -> Self:
        """Return a self instance setting `future` attribute.

        Args:
            timestamps (ArrayLike): Array of future timestamps at each waypoint in the shape of (T).
            confidences (ArrayLike): Array of confidences for each mode in the shape of (M).
            waypoints (ArrayLike): Array of waypoints for each mode in the shape of (M, T, D).

        Returns:
            Self instance after setting `future`.
        """
        self.future = Future(timestamps=timestamps, confidences=confidences, waypoints=waypoints)
        return self

    def __eq__(self, other: Box3D | None) -> bool:
        if other is None:
            return False
        else:
            # NOTE: This comparison might be not enough
            eq = True
            eq &= self.unix_time == other.unix_time
            eq &= self.semantic_label == other.semantic_label
            eq &= self.position == other.position
            eq &= self.rotation == other.rotation
            return eq

    @property
    def size(self) -> Vector3:
        """Return the box size in the order of (width, length, height).

        Returns:
            (width, length, height) values.
        """
        return self.shape.size

    @property
    def footprint(self) -> Polygon:
        return self.shape.footprint

    @property
    def area(self) -> float:
        return self.shape.footprint.area

    @property
    def volume(self) -> float:
        return self.area * self.size[2]

    def translate(self, x: Vector3Like) -> None:
        """Apply a translation.

        Args:
            x (Vector3Like): 3D translation vector in the order of (x, y, z).
        """
        self.position += Vector3(x)

        if self.future is not None:
            self.future.translate(x)

    def rotate(self, q: RotationLike) -> None:
        """Apply a rotation.

        Args:
            q (RotationLike): Rotation quaternion.
        """
        q = to_quaternion(q)
        self.position = np.dot(q.rotation_matrix, self.position)
        self.rotation = q * self.rotation

        if self.velocity is not None:
            self.velocity = np.dot(q.rotation_matrix, self.velocity)

        if self.future is not None:
            self.future.rotate(q)

    def corners(self, box_scale: float = 1.0) -> NDArrayF64:
        """Return the bounding box corners.

        Args:
            box_scale (float, optional): Multiply size by this factor to scale the box.

        Returns:
            First four corners are the ones facing forward. The last four are the ones facing backwards,
                in the shape of (8, 3).
        """
        width, length, height = self.size * box_scale

        # 3D box corners (Convention: x points forward, y to the left, z up.)
        x_corners = 0.5 * length * np.array([1, 1, 1, 1, -1, -1, -1, -1])
        y_corners = 0.5 * width * np.array([1, -1, -1, 1, 1, -1, -1, 1])
        z_corners = 0.5 * height * np.array([1, 1, -1, -1, 1, 1, -1, -1])
        corners = np.vstack((x_corners, y_corners, z_corners))  # (3, 8)

        # Rotate and translate
        return np.dot(self.rotation.rotation_matrix, corners).T + self.position

size property

Return the box size in the order of (width, length, height).

Returns:

Type Description
Vector3

(width, length, height) values.

corners(box_scale=1.0)

Return the bounding box corners.

Parameters:

Name Type Description Default
box_scale float

Multiply size by this factor to scale the box.

1.0

Returns:

Type Description
NDArrayF64

First four corners are the ones facing forward. The last four are the ones facing backwards, in the shape of (8, 3).

Source code in t4_devkit/dataclass/box.py
def corners(self, box_scale: float = 1.0) -> NDArrayF64:
    """Return the bounding box corners.

    Args:
        box_scale (float, optional): Multiply size by this factor to scale the box.

    Returns:
        First four corners are the ones facing forward. The last four are the ones facing backwards,
            in the shape of (8, 3).
    """
    width, length, height = self.size * box_scale

    # 3D box corners (Convention: x points forward, y to the left, z up.)
    x_corners = 0.5 * length * np.array([1, 1, 1, 1, -1, -1, -1, -1])
    y_corners = 0.5 * width * np.array([1, -1, -1, 1, 1, -1, -1, 1])
    z_corners = 0.5 * height * np.array([1, 1, -1, -1, 1, 1, -1, -1])
    corners = np.vstack((x_corners, y_corners, z_corners))  # (3, 8)

    # Rotate and translate
    return np.dot(self.rotation.rotation_matrix, corners).T + self.position

rotate(q)

Apply a rotation.

Parameters:

Name Type Description Default
q RotationLike

Rotation quaternion.

required
Source code in t4_devkit/dataclass/box.py
def rotate(self, q: RotationLike) -> None:
    """Apply a rotation.

    Args:
        q (RotationLike): Rotation quaternion.
    """
    q = to_quaternion(q)
    self.position = np.dot(q.rotation_matrix, self.position)
    self.rotation = q * self.rotation

    if self.velocity is not None:
        self.velocity = np.dot(q.rotation_matrix, self.velocity)

    if self.future is not None:
        self.future.rotate(q)

translate(x)

Apply a translation.

Parameters:

Name Type Description Default
x Vector3Like

3D translation vector in the order of (x, y, z).

required
Source code in t4_devkit/dataclass/box.py
def translate(self, x: Vector3Like) -> None:
    """Apply a translation.

    Args:
        x (Vector3Like): 3D translation vector in the order of (x, y, z).
    """
    self.position += Vector3(x)

    if self.future is not None:
        self.future.translate(x)

with_future(timestamps, confidences, waypoints)

Return a self instance setting future attribute.

Parameters:

Name Type Description Default
timestamps ArrayLike

Array of future timestamps at each waypoint in the shape of (T).

required
confidences ArrayLike

Array of confidences for each mode in the shape of (M).

required
waypoints ArrayLike

Array of waypoints for each mode in the shape of (M, T, D).

required

Returns:

Type Description
Self

Self instance after setting future.

Source code in t4_devkit/dataclass/box.py
def with_future(
    self,
    timestamps: ArrayLike,
    confidences: ArrayLike,
    waypoints: ArrayLike,
) -> Self:
    """Return a self instance setting `future` attribute.

    Args:
        timestamps (ArrayLike): Array of future timestamps at each waypoint in the shape of (T).
        confidences (ArrayLike): Array of confidences for each mode in the shape of (M).
        waypoints (ArrayLike): Array of waypoints for each mode in the shape of (M, T, D).

    Returns:
        Self instance after setting `future`.
    """
    self.future = Future(timestamps=timestamps, confidences=confidences, waypoints=waypoints)
    return self

distance_box(box, tf_matrix)

Return a box distance from base_link.

Parameters:

Name Type Description Default
box BoxLike

A box.

required
tf_matrix HomogeneousMatrix

Transformation matrix.

required

Raises:

Type Description
TypeError

Expecting type of box is Box2D or Box3D.

Returns:

Type Description
float | None

float | None: Return None if the type of box is Box2D and its position is None, otherwise returns distance from base_link.

Source code in t4_devkit/dataclass/box.py
def distance_box(box: BoxLike, tf_matrix: HomogeneousMatrix) -> float | None:
    """Return a box distance from `base_link`.

    Args:
        box (BoxLike): A box.
        tf_matrix (HomogeneousMatrix): Transformation matrix.

    Raises:
        TypeError: Expecting type of box is `Box2D` or `Box3D`.

    Returns:
        float | None: Return `None` if the type of box is `Box2D` and its `position` is `None`,
            otherwise returns distance from `base_link`.
    """
    if isinstance(box, Box2D) and box.position is None:
        return None

    if isinstance(box, Box2D):
        position = tf_matrix.transform(box.position)
    elif isinstance(box, Box3D):
        position, _ = tf_matrix.transform(box.position, box.rotation)
    else:
        raise TypeError(f"Unexpected box type: {type(box)}")

    return np.linalg.norm(position).item()

LidarPointCloud

A dataclass to represent lidar pointcloud.

Attributes:

Name Type Description
points NDArrayFloat

Points matrix in the shape of (4, N).

Source code in t4_devkit/dataclass/pointcloud.py
@define
class LidarPointCloud(PointCloud):
    """A dataclass to represent lidar pointcloud.

    Attributes:
        points (NDArrayFloat): Points matrix in the shape of (4, N).
    """

    @staticmethod
    def num_dims() -> int:
        return 4

    @classmethod
    def from_file(cls, filepath: str, metainfo_filepath: str | None = None) -> Self:
        assert filepath.endswith(".bin"), f"Unexpected filetype: {filepath}"

        scan = np.fromfile(filepath, dtype=np.float32)
        points = scan.reshape((-1, 5))[:, : cls.num_dims()]

        metainfo = (
            PointCloudMetainfo.from_file(metainfo_filepath)
            if metainfo_filepath is not None
            else None
        )

        return cls(points.T, metainfo=metainfo)

PointCloud

Abstract base dataclass for pointcloud data.

Source code in t4_devkit/dataclass/pointcloud.py
@define
class PointCloud:
    """Abstract base dataclass for pointcloud data."""

    points: NDArrayFloat = field(converter=np.array)
    metainfo: PointCloudMetainfo | None = field(default=None)

    @points.validator
    def _check_dims(self, attribute, value) -> None:
        if value.shape[0] != self.num_dims():
            raise ValueError(
                f"Expected point dimension is {self.num_dims()}, but got {value.shape[0]}"
            )

    @metainfo.validator
    def _validate_metainfo(self, attribute, value) -> None:
        """Validate that sources in metainfo form non-overlapping parts covering all points.

        This validator ensures backward compatibility by allowing None metainfo.
        """
        if value is None:
            # Backward compatibility: metainfo is optional
            return

        if not value.sources:
            # No sources to validate
            return

        num_points = self.num_points()

        # Collect all intervals defined by sources
        intervals = []
        for source_info in value.sources:
            source_token = source_info.sensor_token
            idx_begin = source_info.idx_begin
            length = source_info.length
            idx_end = idx_begin + length

            # Check bounds
            if idx_begin < 0:
                raise ValueError(f"Source '{source_token}' has negative idx_begin: {idx_begin}")
            if length < 0:
                raise ValueError(f"Source '{source_token}' has negative length: {length}")
            if idx_end > num_points:
                raise ValueError(
                    f"Source '{source_token}' exceeds point cloud size: "
                    f"idx_begin={idx_begin}, length={length}, but num_points={num_points}"
                )

            intervals.append((idx_begin, idx_end, source_token))

        # Sort intervals by start index
        intervals.sort(key=lambda x: x[0])

        # Check for non-overlapping and complete coverage
        expected_start = 0
        for idx_begin, idx_end, source_token in intervals:
            if idx_begin != expected_start:
                if idx_begin > expected_start:
                    raise ValueError(
                        f"Gap detected: points [{expected_start}:{idx_begin}) are not covered by any source"
                    )
                else:
                    raise ValueError(
                        f"Overlap detected: source '{source_token}' starts at {idx_begin}, "
                        f"but previous source ends at {expected_start}"
                    )
            expected_start = idx_end

        # Check if all points are covered
        if expected_start != num_points:
            raise ValueError(
                f"Incomplete coverage: sources cover up to index {expected_start}, "
                f"but num_points={num_points}"
            )

    @staticmethod
    @abstractmethod
    def num_dims() -> int:
        """Return the number of the point dimensions.

        Returns:
            int: The number of the point dimensions.
        """
        pass

    @classmethod
    @abstractmethod
    def from_file(cls, filepath: str) -> Self:
        """Create an object from pointcloud file.

        Args:
            filepath (str): File path of the pointcloud file.

        Returns:
            Self instance.
        """
        pass

    def num_points(self) -> int:
        """Return the number of points.

        Returns:
            int: _description_
        """
        return self.points.shape[1]

    def translate(self, x: NDArrayFloat) -> None:
        for i in range(3):
            self.points[i, :] = self.points[i, :] + x[i]

    def rotate(self, matrix: NDArrayFloat) -> None:
        self.points[:3, :] = np.dot(matrix, self.points[:3, :])

    def transform(self, matrix: NDArrayFloat) -> None:
        self.points[:3, :] = matrix.dot(
            np.vstack((self.points[:3, :], np.ones(self.num_points())))
        )[:3, :]

from_file(filepath) abstractmethod classmethod

Create an object from pointcloud file.

Parameters:

Name Type Description Default
filepath str

File path of the pointcloud file.

required

Returns:

Type Description
Self

Self instance.

Source code in t4_devkit/dataclass/pointcloud.py
@classmethod
@abstractmethod
def from_file(cls, filepath: str) -> Self:
    """Create an object from pointcloud file.

    Args:
        filepath (str): File path of the pointcloud file.

    Returns:
        Self instance.
    """
    pass

num_dims() abstractmethod staticmethod

Return the number of the point dimensions.

Returns:

Name Type Description
int int

The number of the point dimensions.

Source code in t4_devkit/dataclass/pointcloud.py
@staticmethod
@abstractmethod
def num_dims() -> int:
    """Return the number of the point dimensions.

    Returns:
        int: The number of the point dimensions.
    """
    pass

num_points()

Return the number of points.

Returns:

Name Type Description
int int

description

Source code in t4_devkit/dataclass/pointcloud.py
def num_points(self) -> int:
    """Return the number of points.

    Returns:
        int: _description_
    """
    return self.points.shape[1]

PointCloudMetainfo

A dataclass to represent pointcloud metadata.

Attributes:

Name Type Description
stamp Stamp

Timestamp.

sources list[PointCloudSourceInfo]

List of source information.

Source code in t4_devkit/dataclass/pointcloud.py
@define
class PointCloudMetainfo:
    """A dataclass to represent pointcloud metadata.

    Attributes:
        stamp (Stamp): Timestamp.
        sources (list[PointCloudSourceInfo]): List of source information.
    """

    stamp: Stamp = field(converter=lambda x: Stamp(**x) if isinstance(x, dict) else x)
    sources: list[PointCloudSourceInfo] = field(factory=list)

    @classmethod
    def from_file(cls, filepath: str) -> Self:
        """Create an instance from a JSON file.

        Args:
            filepath (str): Path to the JSON file containing metadata.

        Returns:
            Self: PointCloudMetainfo instance.
        """
        data = load_json(filepath)
        stamp = Stamp(**data["stamp"])
        sources = []
        for source_data in data.get("sources", []):
            sources.append(PointCloudSourceInfo(**source_data))
        return cls(stamp=stamp, sources=sources)

    @property
    def source_tokens(self) -> list[str]:
        """Get the list of source sensor tokens.

        Returns:
            list[str]: List of sensor tokens.
        """
        return [source.sensor_token for source in self.sources]

source_tokens property

Get the list of source sensor tokens.

Returns:

Type Description
list[str]

list[str]: List of sensor tokens.

from_file(filepath) classmethod

Create an instance from a JSON file.

Parameters:

Name Type Description Default
filepath str

Path to the JSON file containing metadata.

required

Returns:

Name Type Description
Self Self

PointCloudMetainfo instance.

Source code in t4_devkit/dataclass/pointcloud.py
@classmethod
def from_file(cls, filepath: str) -> Self:
    """Create an instance from a JSON file.

    Args:
        filepath (str): Path to the JSON file containing metadata.

    Returns:
        Self: PointCloudMetainfo instance.
    """
    data = load_json(filepath)
    stamp = Stamp(**data["stamp"])
    sources = []
    for source_data in data.get("sources", []):
        sources.append(PointCloudSourceInfo(**source_data))
    return cls(stamp=stamp, sources=sources)

PointCloudSourceInfo

A dataclass to represent pointcloud source information.

Attributes:

Name Type Description
sensor_token str

source sensor identifier. References token field from Sensor table.

idx_begin int

Begin index of points for the source in the concatenated pointcloud structure.

length int

Length of points for the source in the concatenated pointcloud structure.

stamp Stamp

Timestamp.

Source code in t4_devkit/dataclass/pointcloud.py
@define
class PointCloudSourceInfo:
    """A dataclass to represent pointcloud source information.

    Attributes:
        sensor_token (str): source sensor identifier. References token field from Sensor table.
        idx_begin (int): Begin index of points for the source in the concatenated pointcloud structure.
        length (int): Length of points for the source in the concatenated pointcloud structure.
        stamp (Stamp): Timestamp.
    """

    sensor_token: str
    idx_begin: int
    length: int
    stamp: Stamp = field(converter=lambda x: Stamp(**x) if isinstance(x, dict) else x)

RadarPointCloud

A dataclass to represent radar pointcloud.

Attributes:

Name Type Description
points NDArrayFloat

Points matrix in the shape of (18, N).

Source code in t4_devkit/dataclass/pointcloud.py
@define
class RadarPointCloud(PointCloud):
    """A dataclass to represent radar pointcloud.

    Attributes:
        points (NDArrayFloat): Points matrix in the shape of (18, N).
    """

    # class variables
    invalid_states: ClassVar[list[int]] = [0]
    dynprop_states: ClassVar[list[int]] = list(range(7))
    ambig_states: ClassVar[list[int]] = [3]

    @staticmethod
    def num_dims() -> int:
        return 18

    @classmethod
    def from_file(
        cls,
        filepath: str,
        invalid_states: list[int] | None = None,
        dynprop_states: list[int] | None = None,
        ambig_states: list[int] | None = None,
        metainfo_filepath: str | None = None,
    ) -> Self:
        assert filepath.endswith(".pcd"), f"Unexpected filetype: {filepath}"

        metadata: list[str] = []
        with open(filepath, "rb") as f:
            for line in f:
                line = line.strip().decode("utf-8")
                metadata.append(line)
                if line.startswith("DATA"):
                    break

            data_binary = f.read()

        # Get the header rows and check if they appear as expected.
        assert metadata[0].startswith("#"), "First line must be comment"
        assert metadata[1].startswith("VERSION"), "Second line must be VERSION"
        sizes = metadata[3].split(" ")[1:]
        types = metadata[4].split(" ")[1:]
        counts = metadata[5].split(" ")[1:]
        width = int(metadata[6].split(" ")[1])
        height = int(metadata[7].split(" ")[1])
        data = metadata[10].split(" ")[1]
        feature_count = len(types)
        assert width > 0
        assert len([c for c in counts if c != c]) == 0, "Error: COUNT not supported!"
        assert height == 1, "Error: height != 0 not supported!"
        assert data == "binary"

        # Lookup table for how to decode the binaries.
        unpacking_lut = {
            "F": {2: "e", 4: "f", 8: "d"},
            "I": {1: "b", 2: "h", 4: "i", 8: "q"},
            "U": {1: "B", 2: "H", 4: "I", 8: "Q"},
        }
        types_str = "".join([unpacking_lut[t][int(s)] for t, s in zip(types, sizes)])

        # Decode each point.
        offset = 0
        point_count = width
        points = []
        for i in range(point_count):
            point = []
            for p in range(feature_count):
                start_p = offset
                end_p = start_p + int(sizes[p])
                assert end_p < len(data_binary)
                point_p = struct.unpack(types_str[p], data_binary[start_p:end_p])[0]
                point.append(point_p)
                offset = end_p
            points.append(point)

        # A NaN in the first point indicates an empty pointcloud.
        point = np.array(points[0])
        if np.any(np.isnan(point)):
            metainfo = (
                PointCloudMetainfo.from_file(metainfo_filepath)
                if metainfo_filepath is not None
                else None
            )
            return cls(np.zeros((feature_count, 0)), metainfo=metainfo)

        # Convert to numpy matrix.
        points = np.array(points).transpose()

        # If no parameters are provided, use default settings.
        invalid_states = cls.invalid_states if invalid_states is None else invalid_states
        dynprop_states = cls.dynprop_states if dynprop_states is None else dynprop_states
        ambig_states = cls.ambig_states if ambig_states is None else ambig_states

        # Filter points with an invalid state.
        valid = [p in invalid_states for p in points[-4, :]]
        points = points[:, valid]

        # Filter by dynProp.
        valid = [p in dynprop_states for p in points[3, :]]
        points = points[:, valid]

        # Filter by ambig_state.
        valid = [p in ambig_states for p in points[11, :]]
        points = points[:, valid]

        metainfo = (
            PointCloudMetainfo.from_file(metainfo_filepath)
            if metainfo_filepath is not None
            else None
        )
        return cls(points, metainfo=metainfo)

SegmentationPointCloud

A dataclass to represent segmentation pointcloud.

Attributes:

Name Type Description
points NDArrayFloat

Points matrix in the shape of (4, N).

labels NDArrayU8

Label matrix.

Source code in t4_devkit/dataclass/pointcloud.py
@define
class SegmentationPointCloud(PointCloud):
    """A dataclass to represent segmentation pointcloud.

    Attributes:
        points (NDArrayFloat): Points matrix in the shape of (4, N).
        labels (NDArrayU8): Label matrix.
    """

    labels: NDArrayU8 = field(converter=lambda x: np.array(x, dtype=np.uint8), kw_only=True)

    @staticmethod
    def num_dims() -> int:
        return 4

    @classmethod
    def from_file(
        cls, point_filepath: str, label_filepath: str, metainfo_filepath: str | None = None
    ) -> Self:
        scan = np.fromfile(point_filepath, dtype=np.float32)
        points = scan.reshape((-1, 5))[:, : cls.num_dims()]
        labels = np.fromfile(label_filepath, dtype=np.uint8)
        metainfo = (
            PointCloudMetainfo.from_file(metainfo_filepath)
            if metainfo_filepath is not None
            else None
        )
        return cls(points.T, labels=labels, metainfo=metainfo)

Stamp

A dataclass to represent timestamp.

Attributes:

Name Type Description
sec int

Seconds.

nanosec int

Nanoseconds.

Source code in t4_devkit/dataclass/pointcloud.py
@define
class Stamp:
    """A dataclass to represent timestamp.

    Attributes:
        sec (int): Seconds.
        nanosec (int): Nanoseconds.
    """

    sec: int
    nanosec: int

    @property
    def in_seconds(self) -> float:
        """Convert timestamp to seconds as a float.

        Returns:
            float: Timestamp in seconds.
        """
        return self.sec + self.nanosec * 1e-9

in_seconds property

Convert timestamp to seconds as a float.

Returns:

Name Type Description
float float

Timestamp in seconds.

Shape

A dataclass to represent the 3D box shape.

Attributes:

Name Type Description
shape_type ShapeType

Box shape type.

size Vector3

Box size in the order of (width, length, height).

footprint Polygon

Polygon of footprint.

Examples:

>>> shape = Shape(
...     shape_type=ShapeType.BOUNDING_BOX,
...     size=[1.0, 1.0, 1.0]
... )
Source code in t4_devkit/dataclass/shape.py
@define
class Shape:
    """A dataclass to represent the 3D box shape.

    Attributes:
        shape_type (ShapeType): Box shape type.
        size (Vector3): Box size in the order of (width, length, height).
        footprint (Polygon): Polygon of footprint.

    Examples:
        >>> shape = Shape(
        ...     shape_type=ShapeType.BOUNDING_BOX,
        ...     size=[1.0, 1.0, 1.0]
        ... )
    """

    shape_type: ShapeType
    size: Vector3 = field(converter=Vector3)
    footprint: Polygon = field(default=None)

    def __attrs_post_init__(self) -> None:
        if self.shape_type == ShapeType.POLYGON and self.footprint is None:
            raise ValueError("`footprint` must be specified for `POLYGON`.")

        if self.footprint is None:
            self.footprint = _calculate_footprint(self.size)

ShapeType

Bases: Enum

Source code in t4_devkit/dataclass/shape.py
@unique
class ShapeType(Enum):
    BOUNDING_BOX = 0
    POLYGON = auto()

    @classmethod
    def from_name(cls, name: str) -> Self:
        """Return an enum object from the name of the member.

        Args:
            name (str): Name of enum member.

        Returns:
            Enum object.
        """
        name = name.upper()
        assert name in cls.__members__, f"Unexpected shape type: {name}."
        return cls.__members__[name]

from_name(name) classmethod

Return an enum object from the name of the member.

Parameters:

Name Type Description Default
name str

Name of enum member.

required

Returns:

Type Description
Self

Enum object.

Source code in t4_devkit/dataclass/shape.py
@classmethod
def from_name(cls, name: str) -> Self:
    """Return an enum object from the name of the member.

    Args:
        name (str): Name of enum member.

    Returns:
        Enum object.
    """
    name = name.upper()
    assert name in cls.__members__, f"Unexpected shape type: {name}."
    return cls.__members__[name]

Future

Bases: ObjectPath

Represent the future trajectory features.

Note that the expected shape of waypoints is (M, T, D).

Attributes:

Name Type Description
timestamps NDArrayInt

Sequence of timestamps (T,).

confidences NDArrayFloat

Confidences array for each mode (M,).

waypoints Trajectory

Waypoints matrix in the shape of (M, T, 3).

Examples:

>>> future = Future(
...     timestamps=[1.0, 2.0]
...     confidences=[1.0],
...     waypoints=[[[1.0, 1.0, 1.0], [2.0, 2.0, 2.0]]],
... )
# Get the number of modes.
>>> len(future)
1
# Access the shape of waypoints matrix: (M, T, 3).
>>> future.shape
(1, 2, 3)
# Access waypoints as subscriptable.
>>> future[0] # for mode0
array([[1., 1., 1.],
       [2., 2., 2.]])
>>> future[0, 0] # point0 at mode0
array([1., 1., 1.])
# Access confidence and waypoints for each mode as iterable.
>>> for i, (timestamp, confidence, waypoints) in future:
...     print(f"Mode{i}: {timestamp}, {confidence}, {waypoints}")
...
Mode0: 1.0, 1.0, [[1. 1. 1.] [2. 2. 2.]]
Source code in t4_devkit/dataclass/trajectory.py
@define
class Future(ObjectPath):
    """Represent the future trajectory features.

    Note that the expected shape of waypoints is (M, T, D).

    Attributes:
        timestamps (NDArrayInt): Sequence of timestamps (T,).
        confidences (NDArrayFloat): Confidences array for each mode (M,).
        waypoints (Trajectory): Waypoints matrix in the shape of (M, T, 3).

    Examples:
        >>> future = Future(
        ...     timestamps=[1.0, 2.0]
        ...     confidences=[1.0],
        ...     waypoints=[[[1.0, 1.0, 1.0], [2.0, 2.0, 2.0]]],
        ... )
        # Get the number of modes.
        >>> len(future)
        1
        # Access the shape of waypoints matrix: (M, T, 3).
        >>> future.shape
        (1, 2, 3)
        # Access waypoints as subscriptable.
        >>> future[0] # for mode0
        array([[1., 1., 1.],
               [2., 2., 2.]])
        >>> future[0, 0] # point0 at mode0
        array([1., 1., 1.])
        # Access confidence and waypoints for each mode as iterable.
        >>> for i, (timestamp, confidence, waypoints) in future:
        ...     print(f"Mode{i}: {timestamp}, {confidence}, {waypoints}")
        ...
        Mode0: 1.0, 1.0, [[1. 1. 1.] [2. 2. 2.]]
    """

ObjectPath

A dataclass to represent object path including timestamps, confidences, and waypoints.

Source code in t4_devkit/dataclass/trajectory.py
@define
class ObjectPath:
    """A dataclass to represent object path including timestamps, confidences, and waypoints."""

    timestamps: NDArrayInt = field(converter=np.array)
    confidences: NDArrayFloat = field(
        converter=np.array,
        validator=validators.deep_iterable((validators.ge(0.0), validators.le(1.0))),
    )
    waypoints: Trajectory = field(converter=Trajectory)

    def __attrs_post_init__(self) -> None:
        self._check_dims()

    def _check_dims(self) -> None:
        # check timestamp length between timestamps and waypoints
        if len(self.timestamps) != self.waypoints.shape[1]:
            raise ValueError(
                "Timestamp length must be the same between `timestamps` and `waypoints`, "
                f"but got timestamps={len(self.timestamps)} and waypoints={self.waypoints.shape[1]}"
            )

        # check mode length between waypoints and confidences
        if self.waypoints.shape[0] != len(self.confidences):
            raise ValueError(
                "Mode length must be the same between `waypoints` and `confidences`, "
                f"but got waypoints={self.waypoints.shape[0]} and confidences={len(self.confidences)}"
            )

    def __len__(self) -> int:
        """Return the number of modes."""
        return len(self.waypoints)

    def __getitem__(self, index: int | slice[int]) -> NDArrayFloat:
        return self.waypoints[index]

    def __iter__(self) -> Generator[tuple[float, NDArrayFloat]]:
        yield from zip(self.confidences, self.waypoints, strict=True)

    @property
    def num_mode(self) -> int:
        """Return the number of trajectory modes.

        Returns:
            int: The number of trajectory modes.
        """
        return self.shape[0]

    @property
    def num_timestamp(self) -> int:
        """Return the number of timestamps.

        Returns:
            int: The number of timestamps.
        """
        return self.shape[1]

    @property
    def shape(self) -> tuple[int, ...]:
        """Return the shape of the waypoints matrix.

        Returns:
            Shape of the matrix (M, T, D).
        """
        return self.waypoints.shape

    def translate(self, x: Vector3Like) -> None:
        """Apply a translation.

        Args:
            x (Vector3Like): 3D translation vector.
        """
        self.waypoints += Vector3(x)

    def rotate(self, q: RotationLike) -> None:
        """Apply a rotation.

        Args:
            q (RotationLike): Rotation quaternion.
        """
        # NOTE: R * X = X * R^T
        q = to_quaternion(q)
        self.waypoints = np.dot(self.waypoints, q.rotation_matrix.T)

num_mode property

Return the number of trajectory modes.

Returns:

Name Type Description
int int

The number of trajectory modes.

num_timestamp property

Return the number of timestamps.

Returns:

Name Type Description
int int

The number of timestamps.

shape property

Return the shape of the waypoints matrix.

Returns:

Type Description
tuple[int, ...]

Shape of the matrix (M, T, D).

__len__()

Return the number of modes.

Source code in t4_devkit/dataclass/trajectory.py
def __len__(self) -> int:
    """Return the number of modes."""
    return len(self.waypoints)

rotate(q)

Apply a rotation.

Parameters:

Name Type Description Default
q RotationLike

Rotation quaternion.

required
Source code in t4_devkit/dataclass/trajectory.py
def rotate(self, q: RotationLike) -> None:
    """Apply a rotation.

    Args:
        q (RotationLike): Rotation quaternion.
    """
    # NOTE: R * X = X * R^T
    q = to_quaternion(q)
    self.waypoints = np.dot(self.waypoints, q.rotation_matrix.T)

translate(x)

Apply a translation.

Parameters:

Name Type Description Default
x Vector3Like

3D translation vector.

required
Source code in t4_devkit/dataclass/trajectory.py
def translate(self, x: Vector3Like) -> None:
    """Apply a translation.

    Args:
        x (Vector3Like): 3D translation vector.
    """
    self.waypoints += Vector3(x)

Past

Bases: ObjectPath

Represent the past trajectory features.

Note that the expected shape of waypoints is (1, T, D).

Attributes:

Name Type Description
timestamps NDArrayInt

Sequence of timestamps (T,).

confidences NDArrayFloat

Confidences array for the mode (1,).

waypoints Trajectory

Waypoints matrix in the shape of (1, T, 3).

Examples:

>>> past = Past(
...     timestamps=[1.0, 2.0]
...     confidences=[1.0],
...     waypoints=[[[1.0, 1.0, 1.0], [2.0, 2.0, 2.0]]],
... )
# Get the number of modes.
>>> len(past)
1
# Access the shape of waypoints matrix: (M, T, 3).
>>> past.shape
(1, 2, 3)
# Access waypoints as subscriptable.
>>> past[0] # for mode0
array([[1., 1., 1.],
       [2., 2., 2.]])
>>> past[0, 0] # point0 at mode0
array([1., 1., 1.])
# Access confidence and waypoints for each mode as iterable.
>>> for i, (timestamp, confidence, waypoints) in past:
...     print(f"Mode{i}: {timestamp}, {confidence}, {waypoints}")
...
Mode0: 1.0, 1.0, [[1. 1. 1.] [2. 2. 2.]]
Source code in t4_devkit/dataclass/trajectory.py
@define
class Past(ObjectPath):
    """Represent the past trajectory features.

    Note that the expected shape of waypoints is (1, T, D).

    Attributes:
        timestamps (NDArrayInt): Sequence of timestamps (T,).
        confidences (NDArrayFloat): Confidences array for the mode (1,).
        waypoints (Trajectory): Waypoints matrix in the shape of (1, T, 3).

    Examples:
        >>> past = Past(
        ...     timestamps=[1.0, 2.0]
        ...     confidences=[1.0],
        ...     waypoints=[[[1.0, 1.0, 1.0], [2.0, 2.0, 2.0]]],
        ... )
        # Get the number of modes.
        >>> len(past)
        1
        # Access the shape of waypoints matrix: (M, T, 3).
        >>> past.shape
        (1, 2, 3)
        # Access waypoints as subscriptable.
        >>> past[0] # for mode0
        array([[1., 1., 1.],
               [2., 2., 2.]])
        >>> past[0, 0] # point0 at mode0
        array([1., 1., 1.])
        # Access confidence and waypoints for each mode as iterable.
        >>> for i, (timestamp, confidence, waypoints) in past:
        ...     print(f"Mode{i}: {timestamp}, {confidence}, {waypoints}")
        ...
        Mode0: 1.0, 1.0, [[1. 1. 1.] [2. 2. 2.]]
    """

    def _check_dims(self) -> None:
        super()._check_dims()

        if self.num_mode != 1:
            raise ValueError(f"The number of modes for past must be 1, but got {self.num_mode}")

HomogeneousMatrix

Source code in t4_devkit/dataclass/transform.py
@define
class HomogeneousMatrix:
    position: Vector3 = field(converter=Vector3)
    rotation: Quaternion = field(converter=to_quaternion)
    src: str = field(validator=validators.instance_of(str))
    dst: str = field(validator=validators.instance_of(str))
    matrix: Matrix4x4 = field(init=False)

    def __attrs_post_init__(self) -> None:
        self.matrix = _generate_homogeneous_matrix(self.position, self.rotation)

    @classmethod
    def as_identity(cls, frame_id: str) -> Self:
        """Construct a new object with identity.

        Args:
            frame_id (str): Frame ID.

        Returns:
            Constructed self instance.
        """
        return cls(np.zeros(3), Quaternion(), frame_id, frame_id)

    @classmethod
    def from_matrix(
        cls,
        matrix: Matrix4x4Like | HomogeneousMatrix,
        src: str | None = None,
        dst: str | None = None,
    ) -> Self:
        """Construct a new object from a homogeneous matrix.

        Args:
            matrix (Matrix4x4Like | HomogeneousMatrix): 4x4 homogeneous matrix.
            src (str | None, optional): Source frame ID.
                This must be specified only if the input matrix is `Matrix4x4Like`.
            dst (str | None, optional): Destination frame ID.
                This must be specified only if the input matrix is `Matrix4x4Like`.

        Returns:
            Constructed self instance.
        """
        position, rotation = _extract_position_and_rotation_from_matrix(matrix)
        if isinstance(matrix, np.ndarray):
            assert matrix.shape == (4, 4)
            assert src is not None and dst is not None
            return cls(position, rotation, src, dst)
        else:
            return cls(position, rotation, matrix.src, matrix.dst)

    @property
    def shape(self) -> tuple[int, ...]:
        """Return a shape of the homogeneous matrix.

        Returns:
            Return the shape of (4, 4).
        """
        return self.matrix.shape

    @property
    def yaw_pitch_roll(self) -> tuple[float, float, float]:
        """Return yaw, pitch and roll.

        NOTE:
            yaw: Rotation angle around the z-axis in [rad], in the range `[-pi, pi]`.
            pitch: Rotation angle around the y'-axis in [rad], in the range `[-pi/2, pi/2]`.
            roll: Rotation angle around the x"-axis in [rad], in the range `[-pi, pi]`.

        Returns:
            Yaw, pitch and roll in [rad].
        """
        return self.rotation.yaw_pitch_roll

    @property
    def rotation_matrix(self) -> Matrix3x3:
        """Return a 3x3 rotation matrix.

        Returns:
            3x3 rotation matrix.
        """
        return self.rotation.rotation_matrix

    def dot(self, other: HomogeneousMatrix) -> HomogeneousMatrix:
        """Return a dot product of myself and another.

        Args:
            other (HomogeneousMatrix): `HomogeneousMatrix` object.

        Raises:
            ValueError: `self.src` and `other.dst` must be the same frame ID.

        Returns:
            Result of a dot product.
        """
        if self.src != other.dst:
            raise ValueError(f"self.src != other.dst: self.src={self.src}, other.dst={other.dst}")

        ret_mat = self.matrix.dot(other.matrix)
        position, rotation = _extract_position_and_rotation_from_matrix(ret_mat)
        return HomogeneousMatrix(position, rotation, src=other.src, dst=self.dst)

    def inv(self) -> HomogeneousMatrix:
        """Return a inverse matrix of myself.

        Returns:
            Inverse matrix.
        """
        ret_mat = np.linalg.inv(self.matrix)
        position, rotation = _extract_position_and_rotation_from_matrix(ret_mat)
        return HomogeneousMatrix(position, rotation, src=self.src, dst=self.dst)

    @overload
    def translate(self, position: Vector3Like) -> Vector3:
        """Translate a position by myself.

        Args:
            position (Vector3Like): 3D position.

        Returns:
            Translated position.
        """
        pass

    @overload
    def translate(self, matrix: HomogeneousMatrix) -> HomogeneousMatrix:
        """Translate a homogeneous matrix by myself.

        Args:
            matrix (HomogeneousMatrix):

        Returns:
            Translated `HomogeneousMatrix` object.
        """
        pass

    def translate(self, *args, **kwargs) -> TranslateItemLike:
        inputs = _format_transform_args(*args, **kwargs)
        if {"position"} == set(inputs.keys()):
            return self.position + inputs["position"]
        elif {"matrix"} == set(inputs.keys()):
            matrix: HomogeneousMatrix = deepcopy(inputs["matrix"])
            matrix.position = self.position + matrix.position
            return matrix
        else:
            raise ValueError(f"Unexpected arguments: {list(inputs.keys())}")

    @overload
    def rotate(self, position: Vector3Like) -> Vector3:
        """Rotate a position by myself.

        Args:
            position (Vector3Like): 3D position.

        Returns:
            Rotated position.
        """
        pass

    @overload
    def rotate(self, rotation: RotationLike) -> Quaternion:
        """Rotate a 3x3 rotation matrix or quaternion by myself.

        Args:
            rotation (RotationLike): 3x3 rotation matrix or quaternion.

        Returns:
            Rotated quaternion.
        """
        pass

    @overload
    def rotate(self, matrix: HomogeneousMatrix) -> HomogeneousMatrix:
        """Rotate a homogeneous matrix by myself.

        Args:
            matrix (HomogeneousMatrix): `HomogeneousMatrix` object.

        Returns:
            Rotated `HomogeneousMatrix` object.
        """
        pass

    def rotate(self, *args, **kwargs) -> RotateItemLike:
        inputs = _format_transform_args(*args, **kwargs)
        if {"position"} == set(inputs.keys()):
            return np.matmul(self.rotation_matrix, inputs["position"])
        elif {"rotation"} == set(inputs.keys()):
            return np.matmul(self.rotation_matrix, inputs["rotation"].rotation_matrix)
        elif {"matrix"} == set(inputs.keys()):
            matrix: HomogeneousMatrix = deepcopy(inputs["matrix"])
            matrix.rotation = Quaternion(
                matrix=np.matmul(self.rotation_matrix, matrix.rotation_matrix)
            )
            return matrix
        else:
            raise ValueError(f"Unexpected arguments: {list(inputs.keys())}")

    @overload
    def transform(self, position: Vector3Like) -> Vector3:
        """Transform a position by myself.

        Args:
            position (ArrayLike): 3D position.

        Returns:
            Transformed position.
        """
        pass

    @overload
    def transform(self, rotation: RotationLike) -> Quaternion:
        """Transform a rotation by myself.

        Args:
            rotation (RotationLike): 3x3 rotation matrix or quaternion.

        Returns:
            Transformed quaternion.
        """
        pass

    @overload
    def transform(
        self,
        position: Vector3Like,
        rotation: RotationLike,
    ) -> tuple[Vector3, Quaternion]:
        """Transform position and rotation by myself.

        Args:
            position (Vector3Like): 3D position.
            rotation (RotationLike): 3x3 rotation matrix or quaternion.

        Returns:
            Transformed position and quaternion.
        """
        pass

    @overload
    def transform(self, matrix: HomogeneousMatrix) -> HomogeneousMatrix:
        """Transform a homogeneous matrix by myself.

        Args:
            matrix (HomogeneousMatrix): `HomogeneousMatrix` object.

        Returns:
            Transformed `HomogeneousMatrix` object.
        """
        pass

    def transform(self, *args, **kwargs) -> TransformItemLike:
        inputs = _format_transform_args(*args, **kwargs)
        if {"position", "rotation"} == set(inputs.keys()):
            return self.__transform_position_and_rotation(**inputs)
        elif {"position"} == set(inputs.keys()):
            return self.__transform_position(**inputs)
        elif {"rotation"} == set(inputs.keys()):
            return self.__transform_rotation(**inputs)
        elif {"matrix"} == set(inputs.keys()):
            return self.__transform_matrix(**inputs)
        else:
            raise ValueError(f"Unexpected inputs: {list(inputs.keys())}")

    def __transform_position(self, position: Vector3Like) -> Vector3:
        rotation = Quaternion()
        matrix = _generate_homogeneous_matrix(position, rotation)
        ret_mat = self.matrix.dot(matrix)
        ret_pos, _ = _extract_position_and_rotation_from_matrix(ret_mat)
        return ret_pos

    def __transform_rotation(self, rotation: RotationLike) -> Quaternion:
        position = np.zeros(3)
        matrix = _generate_homogeneous_matrix(position, rotation)
        ret_mat = self.matrix.dot(matrix)
        _, ret_rot = _extract_position_and_rotation_from_matrix(ret_mat)
        return ret_rot

    def __transform_position_and_rotation(
        self,
        position: Vector3Like,
        rotation: RotationLike,
    ) -> tuple[Vector3, Quaternion]:
        matrix = _generate_homogeneous_matrix(position, rotation)
        ret_mat = self.matrix.dot(matrix)
        return _extract_position_and_rotation_from_matrix(ret_mat)

    def __transform_matrix(self, matrix: HomogeneousMatrix) -> HomogeneousMatrix:
        return matrix.dot(self)

rotation_matrix property

Return a 3x3 rotation matrix.

Returns:

Type Description
Matrix3x3

3x3 rotation matrix.

shape property

Return a shape of the homogeneous matrix.

Returns:

Type Description
tuple[int, ...]

Return the shape of (4, 4).

yaw_pitch_roll property

Return yaw, pitch and roll.

NOTE

yaw: Rotation angle around the z-axis in [rad], in the range [-pi, pi]. pitch: Rotation angle around the y'-axis in [rad], in the range [-pi/2, pi/2]. roll: Rotation angle around the x"-axis in [rad], in the range [-pi, pi].

Returns:

Type Description
tuple[float, float, float]

Yaw, pitch and roll in [rad].

as_identity(frame_id) classmethod

Construct a new object with identity.

Parameters:

Name Type Description Default
frame_id str

Frame ID.

required

Returns:

Type Description
Self

Constructed self instance.

Source code in t4_devkit/dataclass/transform.py
@classmethod
def as_identity(cls, frame_id: str) -> Self:
    """Construct a new object with identity.

    Args:
        frame_id (str): Frame ID.

    Returns:
        Constructed self instance.
    """
    return cls(np.zeros(3), Quaternion(), frame_id, frame_id)

dot(other)

Return a dot product of myself and another.

Parameters:

Name Type Description Default
other HomogeneousMatrix

HomogeneousMatrix object.

required

Raises:

Type Description
ValueError

self.src and other.dst must be the same frame ID.

Returns:

Type Description
HomogeneousMatrix

Result of a dot product.

Source code in t4_devkit/dataclass/transform.py
def dot(self, other: HomogeneousMatrix) -> HomogeneousMatrix:
    """Return a dot product of myself and another.

    Args:
        other (HomogeneousMatrix): `HomogeneousMatrix` object.

    Raises:
        ValueError: `self.src` and `other.dst` must be the same frame ID.

    Returns:
        Result of a dot product.
    """
    if self.src != other.dst:
        raise ValueError(f"self.src != other.dst: self.src={self.src}, other.dst={other.dst}")

    ret_mat = self.matrix.dot(other.matrix)
    position, rotation = _extract_position_and_rotation_from_matrix(ret_mat)
    return HomogeneousMatrix(position, rotation, src=other.src, dst=self.dst)

from_matrix(matrix, src=None, dst=None) classmethod

Construct a new object from a homogeneous matrix.

Parameters:

Name Type Description Default
matrix Matrix4x4Like | HomogeneousMatrix

4x4 homogeneous matrix.

required
src str | None

Source frame ID. This must be specified only if the input matrix is Matrix4x4Like.

None
dst str | None

Destination frame ID. This must be specified only if the input matrix is Matrix4x4Like.

None

Returns:

Type Description
Self

Constructed self instance.

Source code in t4_devkit/dataclass/transform.py
@classmethod
def from_matrix(
    cls,
    matrix: Matrix4x4Like | HomogeneousMatrix,
    src: str | None = None,
    dst: str | None = None,
) -> Self:
    """Construct a new object from a homogeneous matrix.

    Args:
        matrix (Matrix4x4Like | HomogeneousMatrix): 4x4 homogeneous matrix.
        src (str | None, optional): Source frame ID.
            This must be specified only if the input matrix is `Matrix4x4Like`.
        dst (str | None, optional): Destination frame ID.
            This must be specified only if the input matrix is `Matrix4x4Like`.

    Returns:
        Constructed self instance.
    """
    position, rotation = _extract_position_and_rotation_from_matrix(matrix)
    if isinstance(matrix, np.ndarray):
        assert matrix.shape == (4, 4)
        assert src is not None and dst is not None
        return cls(position, rotation, src, dst)
    else:
        return cls(position, rotation, matrix.src, matrix.dst)

inv()

Return a inverse matrix of myself.

Returns:

Type Description
HomogeneousMatrix

Inverse matrix.

Source code in t4_devkit/dataclass/transform.py
def inv(self) -> HomogeneousMatrix:
    """Return a inverse matrix of myself.

    Returns:
        Inverse matrix.
    """
    ret_mat = np.linalg.inv(self.matrix)
    position, rotation = _extract_position_and_rotation_from_matrix(ret_mat)
    return HomogeneousMatrix(position, rotation, src=self.src, dst=self.dst)

TransformBuffer

A buffer class to store transformation matrices.

Attributes:

Name Type Description
buffer dict[tuple[str, str], HomogeneousMatrix]

Matrix buffer whose key is (src, dst).

Source code in t4_devkit/dataclass/transform.py
@define
class TransformBuffer:
    """A buffer class to store transformation matrices.

    Attributes:
        buffer (dict[tuple[str, str], HomogeneousMatrix]): Matrix buffer whose key is `(src, dst)`.
    """

    buffer: dict[tuple[str, str], HomogeneousMatrix] = field(factory=dict, init=False)

    def set_transform(self, matrix: HomogeneousMatrix) -> None:
        """Set transform matrix to the buffer.
        Also, if its inverse transformation has not been registered, registers it too.

        Args:
            matrix (HomogeneousMatrix): Transformation matrix.
        """
        src = matrix.src
        dst = matrix.dst
        if (src, dst) not in self.buffer:
            self.buffer[(src, dst)] = matrix

        if (dst, src) not in self.buffer:
            self.buffer[(dst, src)] = matrix.inv()

    def lookup_transform(self, src: str, dst: str) -> HomogeneousMatrix | None:
        """Look up the transform matrix corresponding to the `src` and `dst` frame ID.

        Args:
            src (str): Source frame ID.
            dst (str): Destination frame ID.

        Returns:
            Returns `HomogeneousMatrix` if the corresponding matrix can be found,
                otherwise it returns `None`.
        """
        if src == dst:
            return HomogeneousMatrix.as_identity(src)
        return self.buffer[(src, dst)] if (src, dst) in self.buffer else None

    def do_translate(self, src: str, dst: str, *args, **kwargs) -> TranslateItemLike | None:
        """Translate specified items with the matrix corresponding to `src` and `dst` frame ID.

        Args:
            src (str): Source frame ID.
            dst (str): Destination frame ID.

        Returns:
            TranslateItemLike | None: Returns translated items if the corresponding matrix can be found,
                otherwise it returns `None`.
        """
        tf_matrix = self.lookup_transform(src, dst)
        return tf_matrix.translate(*args, **kwargs) if tf_matrix is not None else None

    def do_rotate(self, src: str, dst: str, *args, **kwargs) -> RotateItemLike | None:
        """Rotate specified items with the matrix corresponding to `src` and `dst` frame ID.

        Args:
            src (str): Source frame ID.
            dst (str): Destination frame ID.

        Returns:
            TranslateItemLike | None: Returns rotated items if the corresponding matrix can be found,
                otherwise it returns `None`.
        """
        tf_matrix = self.lookup_transform(src, dst)
        return tf_matrix.rotate(*args, **kwargs) if tf_matrix is not None else None

    def do_transform(self, src: str, dst: str, *args, **kwargs) -> TransformItemLike | None:
        """Transform specified items with the matrix corresponding to `src` and `dst` frame ID.

        Args:
            src (str): Source frame ID.
            dst (str): Destination frame ID.

        Returns:
            TranslateItemLike | None: Returns transformed items if the corresponding matrix can be found,
                otherwise it returns `None`.
        """
        tf_matrix = self.lookup_transform(src, dst)
        return tf_matrix.transform(*args, **kwargs) if tf_matrix is not None else None

do_rotate(src, dst, *args, **kwargs)

Rotate specified items with the matrix corresponding to src and dst frame ID.

Parameters:

Name Type Description Default
src str

Source frame ID.

required
dst str

Destination frame ID.

required

Returns:

Type Description
RotateItemLike | None

TranslateItemLike | None: Returns rotated items if the corresponding matrix can be found, otherwise it returns None.

Source code in t4_devkit/dataclass/transform.py
def do_rotate(self, src: str, dst: str, *args, **kwargs) -> RotateItemLike | None:
    """Rotate specified items with the matrix corresponding to `src` and `dst` frame ID.

    Args:
        src (str): Source frame ID.
        dst (str): Destination frame ID.

    Returns:
        TranslateItemLike | None: Returns rotated items if the corresponding matrix can be found,
            otherwise it returns `None`.
    """
    tf_matrix = self.lookup_transform(src, dst)
    return tf_matrix.rotate(*args, **kwargs) if tf_matrix is not None else None

do_transform(src, dst, *args, **kwargs)

Transform specified items with the matrix corresponding to src and dst frame ID.

Parameters:

Name Type Description Default
src str

Source frame ID.

required
dst str

Destination frame ID.

required

Returns:

Type Description
TransformItemLike | None

TranslateItemLike | None: Returns transformed items if the corresponding matrix can be found, otherwise it returns None.

Source code in t4_devkit/dataclass/transform.py
def do_transform(self, src: str, dst: str, *args, **kwargs) -> TransformItemLike | None:
    """Transform specified items with the matrix corresponding to `src` and `dst` frame ID.

    Args:
        src (str): Source frame ID.
        dst (str): Destination frame ID.

    Returns:
        TranslateItemLike | None: Returns transformed items if the corresponding matrix can be found,
            otherwise it returns `None`.
    """
    tf_matrix = self.lookup_transform(src, dst)
    return tf_matrix.transform(*args, **kwargs) if tf_matrix is not None else None

do_translate(src, dst, *args, **kwargs)

Translate specified items with the matrix corresponding to src and dst frame ID.

Parameters:

Name Type Description Default
src str

Source frame ID.

required
dst str

Destination frame ID.

required

Returns:

Type Description
TranslateItemLike | None

TranslateItemLike | None: Returns translated items if the corresponding matrix can be found, otherwise it returns None.

Source code in t4_devkit/dataclass/transform.py
def do_translate(self, src: str, dst: str, *args, **kwargs) -> TranslateItemLike | None:
    """Translate specified items with the matrix corresponding to `src` and `dst` frame ID.

    Args:
        src (str): Source frame ID.
        dst (str): Destination frame ID.

    Returns:
        TranslateItemLike | None: Returns translated items if the corresponding matrix can be found,
            otherwise it returns `None`.
    """
    tf_matrix = self.lookup_transform(src, dst)
    return tf_matrix.translate(*args, **kwargs) if tf_matrix is not None else None

lookup_transform(src, dst)

Look up the transform matrix corresponding to the src and dst frame ID.

Parameters:

Name Type Description Default
src str

Source frame ID.

required
dst str

Destination frame ID.

required

Returns:

Type Description
HomogeneousMatrix | None

Returns HomogeneousMatrix if the corresponding matrix can be found, otherwise it returns None.

Source code in t4_devkit/dataclass/transform.py
def lookup_transform(self, src: str, dst: str) -> HomogeneousMatrix | None:
    """Look up the transform matrix corresponding to the `src` and `dst` frame ID.

    Args:
        src (str): Source frame ID.
        dst (str): Destination frame ID.

    Returns:
        Returns `HomogeneousMatrix` if the corresponding matrix can be found,
            otherwise it returns `None`.
    """
    if src == dst:
        return HomogeneousMatrix.as_identity(src)
    return self.buffer[(src, dst)] if (src, dst) in self.buffer else None

set_transform(matrix)

Set transform matrix to the buffer. Also, if its inverse transformation has not been registered, registers it too.

Parameters:

Name Type Description Default
matrix HomogeneousMatrix

Transformation matrix.

required
Source code in t4_devkit/dataclass/transform.py
def set_transform(self, matrix: HomogeneousMatrix) -> None:
    """Set transform matrix to the buffer.
    Also, if its inverse transformation has not been registered, registers it too.

    Args:
        matrix (HomogeneousMatrix): Transformation matrix.
    """
    src = matrix.src
    dst = matrix.dst
    if (src, dst) not in self.buffer:
        self.buffer[(src, dst)] = matrix

    if (dst, src) not in self.buffer:
        self.buffer[(dst, src)] = matrix.inv()