Skip to content

roverp.readers

Data interfaces for various processed output data formats.

Warning

This module is not automatically imported; you will need to explicitly import it:

from roverp import readers

roverp.readers.Poses dataclass

Discrete sampled poses.

Attributes:

Name Type Description
t Float64[ndarray, N]

timestamp, in seconds.

pos Float64[ndarray, 'N 3']

position, in meters (front-left-up coordinate convention).

vel Float64[ndarray, 'N 3']

velocity, in meters/second.

acc Float64[ndarray, 'N 3']

acceleration, in meters/second^2.

rot Float64[ndarray, 'N 3 3']

rotation (as matrix).

Source code in processing/src/roverp/readers/pose.py
@dataclass(frozen=True)
class Poses:
    """Discrete sampled poses.

    Attributes:
        t: timestamp, in seconds.
        pos: position, in meters (front-left-up coordinate convention).
        vel: velocity, in meters/second.
        acc: acceleration, in meters/second^2.
        rot: rotation (as matrix).
    """

    t: Float64[np.ndarray, "N"]
    pos: Float64[np.ndarray, "N 3"]
    vel: Float64[np.ndarray, "N 3"]
    acc: Float64[np.ndarray, "N 3"]
    rot: Float64[np.ndarray, "N 3 3"]

    def as_dict(self) -> dict[str, Float64[np.ndarray, "N"]]:
        """Convert to a dictionary."""
        return {
            "t": self.t,
            "pos": self.pos,
            "vel": self.vel,
            "acc": self.acc,
            "rot": self.rot,
        }

as_dict

as_dict() -> dict[str, Float64[ndarray, N]]

Convert to a dictionary.

Source code in processing/src/roverp/readers/pose.py
def as_dict(self) -> dict[str, Float64[np.ndarray, "N"]]:
    """Convert to a dictionary."""
    return {
        "t": self.t,
        "pos": self.pos,
        "vel": self.vel,
        "acc": self.acc,
        "rot": self.rot,
    }

roverp.readers.RawTrajectory dataclass

Raw trajectory from cartographer.

Attributes:

Name Type Description
xyz Float64[ndarray, '3 N']

position

quat Float64[ndarray, '4 N']

rotation (as quaternion)

t Float64[ndarray, N]

timestamp

Source code in processing/src/roverp/readers/pose.py
@dataclass(frozen=True)
class RawTrajectory:
    """Raw trajectory from cartographer.

    Attributes:
        xyz: position
        quat: rotation (as quaternion)
        t: timestamp
    """

    xyz: Float64[np.ndarray, "3 N"]
    quat: Float64[np.ndarray, "4 N"]
    t: Float64[np.ndarray, "N"]

    @classmethod
    def from_csv(cls, path: str) -> "RawTrajectory":
        """Load `trajectory.csv` output file.

        Args:
            path: path to the `trajectory.csv` file.
        """
        df = pd.read_csv(path)
        return RawTrajectory(
            xyz=np.stack([
                df["field.transform.translation.{}".format(axis)]
                for axis in "xyz"]),
            quat=np.stack([
                df["field.transform.rotation.{}".format(axis)]
                for axis in "xyzw"]),
            t=np.array(df['field.header.stamp']) / 1e9)  # type: ignore

    def bounds(
        self, margin_xy: float = 5.0, margin_z: float = 5.0,
        resolution: float = 50.0, align: int = 16
    ) -> tuple[
        Float[np.ndarray, "3"],
        Float[np.ndarray, "3"],
        Integer[np.ndarray, "3"]
    ]:
        """Get bounds for a grid containing the extents of the trajectory.

        Args:
            margin_xy: grid margin around trajectory bounds in the
                horizontal plane.
            margin_z: grid margin in the vertical axis.
            resolution: resolution, in grid cells/m.
            align: grid resolution alignment; the grid will be expanded from the
                specified margin until the resolution is divisible by `align`.

        Returns:
            grid lower bound
            grid upper bound
            grid size
        """
        margin = np.array([margin_xy, margin_xy, margin_z])
        lower = np.min(self.xyz, axis=1) - margin
        upper = np.max(self.xyz, axis=1) + margin

        size = ((upper - lower) * resolution + align - 1) // align * align

        round_up = (size / resolution) - (upper - lower)
        lower = lower - round_up / 2
        upper = upper + round_up / 2
        return lower, upper, size.astype(int)

bounds

bounds(
    margin_xy: float = 5.0,
    margin_z: float = 5.0,
    resolution: float = 50.0,
    align: int = 16,
) -> tuple[Float[ndarray, 3], Float[ndarray, 3], Integer[ndarray, 3]]

Get bounds for a grid containing the extents of the trajectory.

Parameters:

Name Type Description Default
margin_xy float

grid margin around trajectory bounds in the horizontal plane.

5.0
margin_z float

grid margin in the vertical axis.

5.0
resolution float

resolution, in grid cells/m.

50.0
align int

grid resolution alignment; the grid will be expanded from the specified margin until the resolution is divisible by align.

16

Returns:

Type Description
Float[ndarray, 3]

grid lower bound

Float[ndarray, 3]

grid upper bound

Integer[ndarray, 3]

grid size

Source code in processing/src/roverp/readers/pose.py
def bounds(
    self, margin_xy: float = 5.0, margin_z: float = 5.0,
    resolution: float = 50.0, align: int = 16
) -> tuple[
    Float[np.ndarray, "3"],
    Float[np.ndarray, "3"],
    Integer[np.ndarray, "3"]
]:
    """Get bounds for a grid containing the extents of the trajectory.

    Args:
        margin_xy: grid margin around trajectory bounds in the
            horizontal plane.
        margin_z: grid margin in the vertical axis.
        resolution: resolution, in grid cells/m.
        align: grid resolution alignment; the grid will be expanded from the
            specified margin until the resolution is divisible by `align`.

    Returns:
        grid lower bound
        grid upper bound
        grid size
    """
    margin = np.array([margin_xy, margin_xy, margin_z])
    lower = np.min(self.xyz, axis=1) - margin
    upper = np.max(self.xyz, axis=1) + margin

    size = ((upper - lower) * resolution + align - 1) // align * align

    round_up = (size / resolution) - (upper - lower)
    lower = lower - round_up / 2
    upper = upper + round_up / 2
    return lower, upper, size.astype(int)

from_csv classmethod

from_csv(path: str) -> RawTrajectory

Load trajectory.csv output file.

Parameters:

Name Type Description Default
path str

path to the trajectory.csv file.

required
Source code in processing/src/roverp/readers/pose.py
@classmethod
def from_csv(cls, path: str) -> "RawTrajectory":
    """Load `trajectory.csv` output file.

    Args:
        path: path to the `trajectory.csv` file.
    """
    df = pd.read_csv(path)
    return RawTrajectory(
        xyz=np.stack([
            df["field.transform.translation.{}".format(axis)]
            for axis in "xyz"]),
        quat=np.stack([
            df["field.transform.rotation.{}".format(axis)]
            for axis in "xyzw"]),
        t=np.array(df['field.header.stamp']) / 1e9)  # type: ignore

roverp.readers.Trajectory

Sensor trajectory.

The provided path should be the output of our cartographer processing pipeline, with the following columns:

  • field.header.stamp (in ns)
  • field.transform.translation.{xyz} (meters)
  • field.transform.rotation.{xyzw} (quaternion, in xyzw order)

Parameters:

Name Type Description Default
path str

Path to cartographer output trajectory.csv file.

required
smoothing float

Smoothing coefficient passed to scipy.interpolate.splprep; is divided by the number of samples N.

10.0
start_threshold float

Start threshold in meters; the trace is started when the sensor moves more than start_threshold from the starting position.

1.0
filter_size int

applies a median filter to the start distance to handle any initalization jitter.

5
Source code in processing/src/roverp/readers/pose.py
class Trajectory:
    """Sensor trajectory.

    The provided path should be the output of our cartographer processing
    pipeline, with the following columns:

    - `field.header.stamp` (in ns)
    - `field.transform.translation.{xyz}` (meters)
    - `field.transform.rotation.{xyzw}` (quaternion, in xyzw order)

    Args:
        path: Path to cartographer output `trajectory.csv` file.
        smoothing: Smoothing coefficient passed to `scipy.interpolate.splprep`;
            is divided by the number of samples `N`.
        start_threshold: Start threshold in meters; the trace is started when
            the sensor moves more than `start_threshold` from the starting
            position.
        filter_size: applies a median filter to the start distance to handle
            any initalization jitter.
    """

    def __init__(
        self, path: str, smoothing: float = 10.0,
        start_threshold: float = 1.0, filter_size: int = 5,
    ) -> None:
        raw = RawTrajectory.from_csv(path)
        origin_dist = medfilt(
            np.linalg.norm(raw.xyz - raw.xyz[0, None], axis=0), filter_size)
        start = np.argmax(origin_dist > start_threshold)
        end = max(np.int64(1), np.argmax(origin_dist[::-1] > start_threshold))

        _t_slam = raw.t[start:-end]

        self.xyz = raw.xyz[:, start:-end]
        self.quat = raw.quat[:, start:-end]
        self.base_time = _t_slam[0]
        self.t_slam = _t_slam - self.base_time

        self.tck, *_ = splprep(
            self.xyz, u=self.t_slam, s=smoothing / self.t_slam.shape[0])
        self.slerp = Slerp(self.t_slam, Rotation.from_quat(self.quat.T))

    def interpolate(
        self, t: Float64[np.ndarray, "N"]
    ) -> tuple[Poses, Bool[np.ndarray, "N"]]:
        """Interpolate trajectory to target timestamps.

        Args:
            t: input timestamps; can be in an arbitrary order.

        Returns:
            Output poses; only indluces poses with valid timestamps.
            A mask indicating valid timestamps.
        """
        t_rel = t - self.base_time
        mask = (t_rel > 0) & (t_rel < self.t_slam[-1])
        t_valid = t_rel[mask]

        pos = np.array(splev(t_valid, self.tck)).T  # type: ignore
        vel = np.array(splev(t_valid, self.tck, der=1)).T  # type: ignore
        acc = np.array(splev(t_valid, self.tck, der=2)).T  # type: ignore
        rot = self.slerp(t_valid).as_matrix()

        return Poses(
            t=t_valid + self.base_time,
            pos=pos, vel=vel, rot=rot, acc=acc), mask

interpolate

interpolate(t: Float64[ndarray, N]) -> tuple[Poses, Bool[ndarray, N]]

Interpolate trajectory to target timestamps.

Parameters:

Name Type Description Default
t Float64[ndarray, N]

input timestamps; can be in an arbitrary order.

required

Returns:

Type Description
Poses

Output poses; only indluces poses with valid timestamps.

Bool[ndarray, N]

A mask indicating valid timestamps.

Source code in processing/src/roverp/readers/pose.py
def interpolate(
    self, t: Float64[np.ndarray, "N"]
) -> tuple[Poses, Bool[np.ndarray, "N"]]:
    """Interpolate trajectory to target timestamps.

    Args:
        t: input timestamps; can be in an arbitrary order.

    Returns:
        Output poses; only indluces poses with valid timestamps.
        A mask indicating valid timestamps.
    """
    t_rel = t - self.base_time
    mask = (t_rel > 0) & (t_rel < self.t_slam[-1])
    t_valid = t_rel[mask]

    pos = np.array(splev(t_valid, self.tck)).T  # type: ignore
    vel = np.array(splev(t_valid, self.tck, der=1)).T  # type: ignore
    acc = np.array(splev(t_valid, self.tck, der=2)).T  # type: ignore
    rot = self.slerp(t_valid).as_matrix()

    return Poses(
        t=t_valid + self.base_time,
        pos=pos, vel=vel, rot=rot, acc=acc), mask

roverp.readers.VoxelGrid

Bases: NamedTuple

Voxel grid of intensities.

Attributes:

Name Type Description
data Float[ndarray, 'Nx Ny Nz']

voxel grid values.

lower Float[ndarray, 3]

coordinate of lower corner.

resolution Float[ndarray, 3]

resolution in units/m for each axis.

Source code in processing/src/roverp/readers/voxelgrid.py
class VoxelGrid(NamedTuple):
    """Voxel grid of intensities.

    Attributes:
        data: voxel grid values.
        lower: coordinate of lower corner.
        resolution: resolution in units/m for each axis.
    """

    data: Float[np.ndarray, "Nx Ny Nz"]
    lower: Float[np.ndarray, "3"]
    resolution: Float[np.ndarray, "3"]

    @classmethod
    def from_npz(
        cls, path: str, key: str = "sigma", decimate: int = 1
    ) -> "VoxelGrid":
        """Load voxel grid, applying decimation factor if specified.

        Args:
            path: path to `.npz` file. Must have the specified `key`, as well
                as a `lower` and `resolution` array.
            key: field to load.
            decimate: decimation factor to apply.
        """
        npz = np.load(path)
        data = np.array(npz[key])

        if decimate > 1:
            data = einsum(
                rearrange(
                    data, "(Nx dy) (Ny dx) (Nz dz) -> Nx Ny Nz (dx dy dz)",
                    dx=decimate, dy=decimate, dz=decimate),
                "Nx Ny Nz d -> Nx Ny Nz")

        resolution = npz["resolution"] / decimate
        if len(resolution.shape) == 0:
            resolution = resolution.reshape(1)

        return cls(data=data, lower=npz["lower"], resolution=resolution)

    def crop(
        self, left: tuple[int, int, int] | None = None,
        right: tuple[int, int, int] | None = None
    ) -> "VoxelGrid":
        """Crop voxel grid by integer lower and upper indices.

        Args:
            left: lower indices.
            right: upper; `right` is interpreted as an ordinary index limit, so
                can be negative.
        """
        lower = self.lower
        data = self.data

        if left is not None:
            assert np.all(np.array(left) >= 0)
            data = data[left[0]:, left[1]:, left[2]:]
            lower = lower + np.array(left) / self.resolution
        if right is not None:
            data = data[:right[0], :right[1], :right[2]]

        return VoxelGrid(data=data, lower=lower, resolution=self.resolution)

    def cfar(
        self, guard_band: int = 1, window_size: int = 3,
        convolve_func=default_conv
    ) -> "VoxelGrid":
        """Get CFAR conv comparison values.

        Args:
            guard_band: CFAR guard band size.
            window_size: CFAR window shape.
            convolve_func: convolution backend to use.
        """
        mask = np.ones([2 * window_size + 1] * 3)
        ax = slice(window_size - guard_band, window_size + guard_band + 1)
        mask[ax, ax, ax] = 0
        mask /= np.sum(mask)

        return VoxelGrid(
            data=convolve_func(self.data, mask, mode='same'), lower=self.lower,
            resolution=self.resolution)

    def normalize(
        self, left: float = 10.0, right: float = 99.9
    ) -> "VoxelGrid":
        """Normalize to (0, 1).

        Args:
            left: lower percentile to clip to.
            right: upper percentile to clip to.
        """
        ll, rr = np.percentile(self.data, [left, right])
        return VoxelGrid(
            data=np.clip((self.data - ll) / (rr - ll), 0.0, 1.0),
            lower=self.lower, resolution=self.resolution)

    def as_pointcloud(
        self, mask: Bool[np.ndarray, "Nx Ny Nz"], cmap: str = 'inferno'
    ) -> tuple[Float[np.ndarray, "3"], UInt8[np.ndarray, "3"]]:
        """Convert voxel grid to point cloud.

        Args:
            mask: mask of voxels to include.
            cmap: matplotlib colormap to use.

        Returns:
            xyz: point positions.
            rgb: point colors.
        """
        colors = matplotlib.colormaps[cmap]

        ixyz = np.stack(np.where(mask))
        rgb = colors(self.data[ixyz[0], ixyz[1], ixyz[2]])[:, :3]
        rgb_u8 = (rgb * 255).astype(np.uint8)

        xyz = self.lower[:, None] + ixyz / self.resolution[:, None]

        return xyz, rgb_u8

    def as_pcd(
        self, path: str, mask: Bool[np.ndarray, "Nx Ny Nz"],
        cmap: str = 'inferno'
    ) -> None:
        """Save as a .pcd file.

        !!! warning

            This method requires `pypcd4` to be installed, e.g. via the `pcd`
            extra:
            ```sh
            pip install roverp[pcd]
            ```

        Args:
            path: output path (ending with .pcd).
            mask: pointcloud mask.
            cmap: pointcloud colors.
        """
        from pypcd4 import PointCloud  # type: ignore

        xyz, rgb = self.as_pointcloud(mask, cmap=cmap)
        rgb_packed = PointCloud.encode_rgb(rgb)
        pc = PointCloud.from_xyzrgb_points([*xyz, rgb_packed])  # type: ignore
        pc.save(path)

    def as_ply(
        self, path: str, mask: Bool[np.ndarray, "Nx Ny Nz"],
        cmap: str = 'inferno'
    ) -> None:
        """Save as a .ply file.

        !!! warning

            This method requires `plyfile` to be installed, e.g. via the `ply`
            extra:
            ```sh
            pip install roverp[ply]
            ```

        Args:
            path: output path (ending with .ply).
            mask: pointcloud mask.
            cmap: pointcloud colors.
        """
        from plyfile import PlyData, PlyElement  # type: ignore

        xyz, rgb = self.as_pointcloud(mask, cmap=cmap)

        vertex = np.zeros(
            xyz.shape[1], dtype=[
            ('x', 'f4'), ('y', 'f4'), ('z', 'f4'),
            ('red', 'u1'), ('green', 'u1'), ('blue', 'u1')
        ])
        vertex['x'] = xyz[0]
        vertex['y'] = xyz[1]
        vertex['z'] = xyz[2]
        vertex['red'] = rgb[:, 0]
        vertex['green'] = rgb[:, 1]
        vertex['blue'] = rgb[:, 2]
        el = PlyElement.describe(
            vertex, 'vertex', comments=['vertices with color'])
        PlyData([el], text=True).write(path)

as_pcd

as_pcd(
    path: str, mask: Bool[ndarray, "Nx Ny Nz"], cmap: str = "inferno"
) -> None

Save as a .pcd file.

Warning

This method requires pypcd4 to be installed, e.g. via the pcd extra:

pip install roverp[pcd]

Parameters:

Name Type Description Default
path str

output path (ending with .pcd).

required
mask Bool[ndarray, 'Nx Ny Nz']

pointcloud mask.

required
cmap str

pointcloud colors.

'inferno'
Source code in processing/src/roverp/readers/voxelgrid.py
def as_pcd(
    self, path: str, mask: Bool[np.ndarray, "Nx Ny Nz"],
    cmap: str = 'inferno'
) -> None:
    """Save as a .pcd file.

    !!! warning

        This method requires `pypcd4` to be installed, e.g. via the `pcd`
        extra:
        ```sh
        pip install roverp[pcd]
        ```

    Args:
        path: output path (ending with .pcd).
        mask: pointcloud mask.
        cmap: pointcloud colors.
    """
    from pypcd4 import PointCloud  # type: ignore

    xyz, rgb = self.as_pointcloud(mask, cmap=cmap)
    rgb_packed = PointCloud.encode_rgb(rgb)
    pc = PointCloud.from_xyzrgb_points([*xyz, rgb_packed])  # type: ignore
    pc.save(path)

as_ply

as_ply(
    path: str, mask: Bool[ndarray, "Nx Ny Nz"], cmap: str = "inferno"
) -> None

Save as a .ply file.

Warning

This method requires plyfile to be installed, e.g. via the ply extra:

pip install roverp[ply]

Parameters:

Name Type Description Default
path str

output path (ending with .ply).

required
mask Bool[ndarray, 'Nx Ny Nz']

pointcloud mask.

required
cmap str

pointcloud colors.

'inferno'
Source code in processing/src/roverp/readers/voxelgrid.py
def as_ply(
    self, path: str, mask: Bool[np.ndarray, "Nx Ny Nz"],
    cmap: str = 'inferno'
) -> None:
    """Save as a .ply file.

    !!! warning

        This method requires `plyfile` to be installed, e.g. via the `ply`
        extra:
        ```sh
        pip install roverp[ply]
        ```

    Args:
        path: output path (ending with .ply).
        mask: pointcloud mask.
        cmap: pointcloud colors.
    """
    from plyfile import PlyData, PlyElement  # type: ignore

    xyz, rgb = self.as_pointcloud(mask, cmap=cmap)

    vertex = np.zeros(
        xyz.shape[1], dtype=[
        ('x', 'f4'), ('y', 'f4'), ('z', 'f4'),
        ('red', 'u1'), ('green', 'u1'), ('blue', 'u1')
    ])
    vertex['x'] = xyz[0]
    vertex['y'] = xyz[1]
    vertex['z'] = xyz[2]
    vertex['red'] = rgb[:, 0]
    vertex['green'] = rgb[:, 1]
    vertex['blue'] = rgb[:, 2]
    el = PlyElement.describe(
        vertex, 'vertex', comments=['vertices with color'])
    PlyData([el], text=True).write(path)

as_pointcloud

as_pointcloud(
    mask: Bool[ndarray, "Nx Ny Nz"], cmap: str = "inferno"
) -> tuple[Float[ndarray, 3], UInt8[ndarray, 3]]

Convert voxel grid to point cloud.

Parameters:

Name Type Description Default
mask Bool[ndarray, 'Nx Ny Nz']

mask of voxels to include.

required
cmap str

matplotlib colormap to use.

'inferno'

Returns:

Name Type Description
xyz Float[ndarray, 3]

point positions.

rgb UInt8[ndarray, 3]

point colors.

Source code in processing/src/roverp/readers/voxelgrid.py
def as_pointcloud(
    self, mask: Bool[np.ndarray, "Nx Ny Nz"], cmap: str = 'inferno'
) -> tuple[Float[np.ndarray, "3"], UInt8[np.ndarray, "3"]]:
    """Convert voxel grid to point cloud.

    Args:
        mask: mask of voxels to include.
        cmap: matplotlib colormap to use.

    Returns:
        xyz: point positions.
        rgb: point colors.
    """
    colors = matplotlib.colormaps[cmap]

    ixyz = np.stack(np.where(mask))
    rgb = colors(self.data[ixyz[0], ixyz[1], ixyz[2]])[:, :3]
    rgb_u8 = (rgb * 255).astype(np.uint8)

    xyz = self.lower[:, None] + ixyz / self.resolution[:, None]

    return xyz, rgb_u8

cfar

cfar(
    guard_band: int = 1, window_size: int = 3, convolve_func=convolve
) -> VoxelGrid

Get CFAR conv comparison values.

Parameters:

Name Type Description Default
guard_band int

CFAR guard band size.

1
window_size int

CFAR window shape.

3
convolve_func

convolution backend to use.

convolve
Source code in processing/src/roverp/readers/voxelgrid.py
def cfar(
    self, guard_band: int = 1, window_size: int = 3,
    convolve_func=default_conv
) -> "VoxelGrid":
    """Get CFAR conv comparison values.

    Args:
        guard_band: CFAR guard band size.
        window_size: CFAR window shape.
        convolve_func: convolution backend to use.
    """
    mask = np.ones([2 * window_size + 1] * 3)
    ax = slice(window_size - guard_band, window_size + guard_band + 1)
    mask[ax, ax, ax] = 0
    mask /= np.sum(mask)

    return VoxelGrid(
        data=convolve_func(self.data, mask, mode='same'), lower=self.lower,
        resolution=self.resolution)

crop

crop(
    left: tuple[int, int, int] | None = None,
    right: tuple[int, int, int] | None = None,
) -> VoxelGrid

Crop voxel grid by integer lower and upper indices.

Parameters:

Name Type Description Default
left tuple[int, int, int] | None

lower indices.

None
right tuple[int, int, int] | None

upper; right is interpreted as an ordinary index limit, so can be negative.

None
Source code in processing/src/roverp/readers/voxelgrid.py
def crop(
    self, left: tuple[int, int, int] | None = None,
    right: tuple[int, int, int] | None = None
) -> "VoxelGrid":
    """Crop voxel grid by integer lower and upper indices.

    Args:
        left: lower indices.
        right: upper; `right` is interpreted as an ordinary index limit, so
            can be negative.
    """
    lower = self.lower
    data = self.data

    if left is not None:
        assert np.all(np.array(left) >= 0)
        data = data[left[0]:, left[1]:, left[2]:]
        lower = lower + np.array(left) / self.resolution
    if right is not None:
        data = data[:right[0], :right[1], :right[2]]

    return VoxelGrid(data=data, lower=lower, resolution=self.resolution)

from_npz classmethod

from_npz(path: str, key: str = 'sigma', decimate: int = 1) -> VoxelGrid

Load voxel grid, applying decimation factor if specified.

Parameters:

Name Type Description Default
path str

path to .npz file. Must have the specified key, as well as a lower and resolution array.

required
key str

field to load.

'sigma'
decimate int

decimation factor to apply.

1
Source code in processing/src/roverp/readers/voxelgrid.py
@classmethod
def from_npz(
    cls, path: str, key: str = "sigma", decimate: int = 1
) -> "VoxelGrid":
    """Load voxel grid, applying decimation factor if specified.

    Args:
        path: path to `.npz` file. Must have the specified `key`, as well
            as a `lower` and `resolution` array.
        key: field to load.
        decimate: decimation factor to apply.
    """
    npz = np.load(path)
    data = np.array(npz[key])

    if decimate > 1:
        data = einsum(
            rearrange(
                data, "(Nx dy) (Ny dx) (Nz dz) -> Nx Ny Nz (dx dy dz)",
                dx=decimate, dy=decimate, dz=decimate),
            "Nx Ny Nz d -> Nx Ny Nz")

    resolution = npz["resolution"] / decimate
    if len(resolution.shape) == 0:
        resolution = resolution.reshape(1)

    return cls(data=data, lower=npz["lower"], resolution=resolution)

normalize

normalize(left: float = 10.0, right: float = 99.9) -> VoxelGrid

Normalize to (0, 1).

Parameters:

Name Type Description Default
left float

lower percentile to clip to.

10.0
right float

upper percentile to clip to.

99.9
Source code in processing/src/roverp/readers/voxelgrid.py
def normalize(
    self, left: float = 10.0, right: float = 99.9
) -> "VoxelGrid":
    """Normalize to (0, 1).

    Args:
        left: lower percentile to clip to.
        right: upper percentile to clip to.
    """
    ll, rr = np.percentile(self.data, [left, right])
    return VoxelGrid(
        data=np.clip((self.data - ll) / (rr - ll), 0.0, 1.0),
        lower=self.lower, resolution=self.resolution)