pointcloud

package
v0.27.1 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: May 14, 2024 License: AGPL-3.0 Imports: 40 Imported by: 13

Documentation

Overview

Package pointcloud defines a point cloud and provides an implementation for one.

Its implementation is dictionary based is not yet efficient. The current focus is to make it useful and as such the API is experimental and subject to change considerably.

Index

Constants

This section is empty.

Variables

This section is empty.

Functions

func BoundingBoxFromPointCloud

func BoundingBoxFromPointCloud(cloud PointCloud) (spatialmath.Geometry, error)

BoundingBoxFromPointCloud returns a Geometry object that encompasses all the points in the given point cloud.

func BoundingBoxFromPointCloudWithLabel added in v0.1.2

func BoundingBoxFromPointCloudWithLabel(cloud PointCloud, label string) (spatialmath.Geometry, error)

BoundingBoxFromPointCloudWithLabel returns a Geometry object that encompasses all the points in the given point cloud.

func CloudCentroid

func CloudCentroid(pc PointCloud) r3.Vector

CloudCentroid returns the centroid of a pointcloud as a vector.

func CloudContains

func CloudContains(cloud PointCloud, x, y, z float64) bool

CloudContains is a silly helper method.

func GetOffset

func GetOffset(center, normal r3.Vector) float64

GetOffset computes the offset of the plane with given normal vector and a point in it.

func GetResidual

func GetResidual(points []r3.Vector, plane Plane) float64

GetResidual computes the mean fitting error of points to a given plane.

func GetVoxelCenter

func GetVoxelCenter(points []r3.Vector) r3.Vector

GetVoxelCenter computes the barycenter of the points in the slice of r3.Vector.

func GetWeight

func GetWeight(points []r3.Vector, lam, residual float64) float64

GetWeight computes weights for Region Growing segmentation.

func NewVector

func NewVector(x, y, z float64) r3.Vector

NewVector convenience method for creating a vector.

func RegisterPointCloudICP

func RegisterPointCloudICP(pcSrc PointCloud, target *KDTree, guess spatialmath.Pose, debug bool, numThreads int,
) (PointCloud, IcpMergeResultInfo, error)

RegisterPointCloudICP registers a source pointcloud to a target pointcloud, starting from an initial guess using ICP.

func ReverseVoxelSlice

func ReverseVoxelSlice(s VoxelSlice)

ReverseVoxelSlice reverses a slice of voxels.

func StatisticalOutlierFilter

func StatisticalOutlierFilter(meanK int, stdDevThresh float64) (func(PointCloud) (PointCloud, error), error)

StatisticalOutlierFilter implements the function from PCL to remove noisy points from a point cloud. https://pcl.readthedocs.io/projects/tutorials/en/latest/statistical_outlier.html This returns a function that can be used to filter on point clouds. NOTE(bh): Returns a new point cloud, but could be modified to filter and change the original point cloud.

func ToPCD

func ToPCD(cloud PointCloud, out io.Writer, outputType PCDType) error

ToPCD writes out a point cloud to a PCD file of the specified type.

func WriteToLASFile

func WriteToLASFile(cloud PointCloud, fn string) (err error)

WriteToLASFile writes the point cloud out to a LAS file.

Types

type BasicOctree added in v0.2.14

type BasicOctree struct {
	// contains filtered or unexported fields
}

BasicOctree is a data structure that represents a basic octree structure with information regarding center point, side length and node data. An octree is a data structure that recursively partitions 3D space into octants to represent occupancy. It is a storage format for a pointcloud that allows for better searchability and serialization.

func NewBasicOctree added in v0.2.14

func NewBasicOctree(center r3.Vector, sideLength float64) (*BasicOctree, error)

NewBasicOctree creates a new basic octree with specified center, side and metadata.

func ReadPCDToBasicOctree added in v0.2.14

func ReadPCDToBasicOctree(inRaw io.Reader) (*BasicOctree, error)

ReadPCDToBasicOctree reads a PCD file into a basic octree.

func (*BasicOctree) AlmostEqual added in v0.4.0

func (octree *BasicOctree) AlmostEqual(geom spatialmath.Geometry) bool

AlmostEqual compares the octree with another geometry and checks if they are equivalent. Note that this checks that the *geometry* is equal; that is, both octrees have the same number of points and in the same locations. This is agnostic to things like the label, the centerpoint (as the individual points have locations), the side lengths, etc.

func (*BasicOctree) At added in v0.2.14

func (octree *BasicOctree) At(x, y, z float64) (Data, bool)

At traverses a basic octree to see if a point exists at the specified location. If a point does exist, its data is returned along with true. If a point does not exist, no data is returned and the boolean is returned false.

func (*BasicOctree) CollidesWith added in v0.4.0

func (octree *BasicOctree) CollidesWith(geom spatialmath.Geometry, collisionBufferMM float64) (bool, error)

CollidesWith checks if the given octree collides with the given geometry and returns true if it does.

func (*BasicOctree) CollidesWithGeometry added in v0.2.34

func (octree *BasicOctree) CollidesWithGeometry(
	geom spatialmath.Geometry,
	confidenceThreshold int,
	buffer,
	collisionBufferMM float64,
) (bool, error)

CollidesWithGeometry will return whether a given geometry is in collision with a given point. A point is in collision if its stored probability is >= confidenceThreshold and if it is at most buffer distance away.

func (*BasicOctree) DistanceFrom added in v0.4.0

func (octree *BasicOctree) DistanceFrom(geom spatialmath.Geometry) (float64, error)

DistanceFrom returns the distance from the given octree to the given geometry. TODO (RSDK-3743): Implement BasicOctree Geometry functions.

func (*BasicOctree) EncompassedBy added in v0.4.0

func (octree *BasicOctree) EncompassedBy(geom spatialmath.Geometry) (bool, error)

EncompassedBy returns true if the given octree is within the given geometry. TODO (RSDK-3743): Implement BasicOctree Geometry functions.

func (*BasicOctree) Iterate added in v0.2.14

func (octree *BasicOctree) Iterate(numBatches, currentBatch int, fn func(p r3.Vector, d Data) bool)

Iterate is a batchable process that will go through a basic octree and applies a specified function to either all the data points or a subset of them based on the given numBatches and currentBatch inputs. If any of the applied functions returns a false value, iteration will stop and no further points will be processed.

func (*BasicOctree) Label added in v0.4.0

func (octree *BasicOctree) Label() string

Label returns the label of this octree.

func (*BasicOctree) MarshalJSON added in v0.4.0

func (octree *BasicOctree) MarshalJSON() ([]byte, error)

MarshalJSON marshals JSON from the octree. TODO (RSDK-3743): Implement BasicOctree Geometry functions.

func (*BasicOctree) MaxVal added in v0.2.31

func (octree *BasicOctree) MaxVal() int

MaxVal returns the max value of all children's data for the passed in octree.

func (*BasicOctree) MetaData added in v0.2.14

func (octree *BasicOctree) MetaData() MetaData

MetaData returns the metadata of the pointcloud stored in the octree.

func (*BasicOctree) Pose added in v0.4.0

func (octree *BasicOctree) Pose() spatialmath.Pose

Pose returns the pose of the octree.

func (*BasicOctree) Set added in v0.2.14

func (octree *BasicOctree) Set(p r3.Vector, d Data) error

Set recursively iterates through a basic octree, attempting to add a given point and data to the tree after ensuring it falls within the bounds of the given basic octree.

func (*BasicOctree) SetLabel added in v0.4.0

func (octree *BasicOctree) SetLabel(label string)

SetLabel sets the label of this octree.

func (*BasicOctree) Size added in v0.2.14

func (octree *BasicOctree) Size() int

Size returns the number of points stored in the octree's metadata.

func (*BasicOctree) String added in v0.4.0

func (octree *BasicOctree) String() string

String returns a human readable string that represents this octree. octree's children will not be represented in the string.

func (*BasicOctree) ToPoints added in v0.4.0

func (octree *BasicOctree) ToPoints(resolution float64) []r3.Vector

ToPoints converts an octree geometry into []r3.Vector.

func (*BasicOctree) ToProtobuf added in v0.4.0

func (octree *BasicOctree) ToProtobuf() *commonpb.Geometry

ToProtobuf converts the octree to a Geometry proto message. TODO (RSDK-3743): Implement BasicOctree Geometry functions.

func (*BasicOctree) Transform added in v0.4.0

func (octree *BasicOctree) Transform(pose spatialmath.Pose) spatialmath.Geometry

Transform recursively steps through the octree and transforms it by the given pose.

type CloudAndOffsetFunc added in v0.1.5

type CloudAndOffsetFunc func(context context.Context) (PointCloud, spatialmath.Pose, error)

CloudAndOffsetFunc is a function that returns a PointCloud with a pose that represents an offset to be applied to every point.

type CloudMatrixCol

type CloudMatrixCol int

CloudMatrixCol is a type that represents the columns of a CloudMatrix.

const (
	// CloudMatrixColX is the x column in the cloud matrix.
	CloudMatrixColX CloudMatrixCol = 0
	// CloudMatrixColY is the y column in the cloud matrix.
	CloudMatrixColY CloudMatrixCol = 1
	// CloudMatrixColZ is the z column in the cloud matrix.
	CloudMatrixColZ CloudMatrixCol = 2
	// CloudMatrixColR is the r column in the cloud matrix.
	CloudMatrixColR CloudMatrixCol = 3
	// CloudMatrixColG is the g column in the cloud matrix.
	CloudMatrixColG CloudMatrixCol = 4
	// CloudMatrixColB is the b column in the cloud matrix.
	CloudMatrixColB CloudMatrixCol = 5
	// CloudMatrixColV is the value column in the cloud matrix.
	CloudMatrixColV CloudMatrixCol = 6
)

func CloudMatrix

func CloudMatrix(pc PointCloud) (*mat.Dense, []CloudMatrixCol)

CloudMatrix Returns a Matrix representation of a Cloud along with a Header list. The Header list is a list of CloudMatrixCols that correspond to the columns in the matrix. CloudMatrix is not guaranteed to return points in the same order as the cloud.

type Data

type Data interface {
	// HasColor returns whether or not this point is colored.
	HasColor() bool

	// RGB255 returns, if colored, the RGB components of the color. There
	// is no alpha channel right now and as such the data can be assumed to be
	// premultiplied.
	RGB255() (uint8, uint8, uint8)

	// Color returns the native color of the point.
	Color() color.Color

	// SetColor sets the given color on the point.
	// Note(erd): we should try to remove this in favor of immutability.
	SetColor(c color.NRGBA) Data

	// HasValue returns whether or not this point has some user data value
	// associated with it.
	HasValue() bool

	// Value returns the user data set value, if it exists.
	Value() int

	// SetValue sets the given user data value on the point.
	// Note(erd): we should try to remove this in favor of immutability.
	SetValue(v int) Data

	// Intensity returns the intensity value, or 0 if it doesn't exist
	Intensity() uint16

	// SetIntensity sets the intensity on the point.
	SetIntensity(v uint16) Data
}

Data describes data associated single point within a PointCloud.

func NewBasicData

func NewBasicData() Data

NewBasicData returns a point that is solely positionally based.

func NewColoredData

func NewColoredData(c color.NRGBA) Data

NewColoredData returns a point that has both position and color.

func NewValueData

func NewValueData(v int) Data

NewValueData returns a point that has both position and a user data value.

type IcpMergeResultInfo

type IcpMergeResultInfo struct {
	X0        []float64
	OptResult optimize.Result
}

IcpMergeResultInfo is a struct to hold the results of registering a pointcloud.

type KDTree

type KDTree struct {
	// contains filtered or unexported fields
}

KDTree extends PointCloud and orders the points in 3D space to implement nearest neighbor algos.

func NewKDTree

func NewKDTree() *KDTree

NewKDTree creates a new KDTree.

func NewKDTreeWithPrealloc

func NewKDTreeWithPrealloc(size int) *KDTree

NewKDTreeWithPrealloc creates a new KDTree with preallocated storage.

func ReadPCDToKDTree

func ReadPCDToKDTree(inRaw io.Reader) (*KDTree, error)

ReadPCDToKDTree reads a PCD file into a KD Tree pointcloud.

func ToKDTree

func ToKDTree(pc PointCloud) *KDTree

ToKDTree creates a KDTree from an input PointCloud.

func (*KDTree) At

func (kd *KDTree) At(x, y, z float64) (Data, bool)

At gets the point at position (x,y,z) from the PointCloud. It returns the data of the nearest neighbor and a boolean representing whether there is a point at that position.

func (*KDTree) Iterate

func (kd *KDTree) Iterate(numBatches, myBatch int, fn func(p r3.Vector, d Data) bool)

Iterate iterates over all points in the cloud.

func (*KDTree) KNearestNeighbors

func (kd *KDTree) KNearestNeighbors(p r3.Vector, k int, includeSelf bool) []*PointAndData

KNearestNeighbors returns the k nearest points ordered by distance. if includeSelf is true and if the point p is in the point cloud, point p will also be returned in the slice as the first element with distance 0.

func (*KDTree) MetaData

func (kd *KDTree) MetaData() MetaData

MetaData returns the meta data.

func (*KDTree) NearestNeighbor

func (kd *KDTree) NearestNeighbor(p r3.Vector) (r3.Vector, Data, float64, bool)

NearestNeighbor returns the nearest point and its distance from the input point.

func (*KDTree) RadiusNearestNeighbors

func (kd *KDTree) RadiusNearestNeighbors(p r3.Vector, r float64, includeSelf bool) []*PointAndData

RadiusNearestNeighbors returns the nearest points within a radius r (inclusive) ordered by distance. If includeSelf is true and if the point p is in the point cloud, point p will also be returned in the slice as the first element with distance 0.

func (*KDTree) Set

func (kd *KDTree) Set(p r3.Vector, d Data) error

Set adds a new point to the PointCloud and tree. Does not rebalance the tree.

func (*KDTree) Size

func (kd *KDTree) Size() int

Size returns the size of the pointcloud.

type MetaData

type MetaData struct {
	HasColor bool
	HasValue bool

	MinX, MaxX float64
	MinY, MaxY float64
	MinZ, MaxZ float64
	// contains filtered or unexported fields
}

MetaData is data about what's stored in the point cloud.

func GetPCDMetaData added in v0.2.28

func GetPCDMetaData(inRaw io.Reader) (MetaData, error)

GetPCDMetaData returns the metadata for the PCD read from the provided reader.

func NewMetaData

func NewMetaData() MetaData

NewMetaData creates a new MetaData.

func (*MetaData) Merge

func (meta *MetaData) Merge(v r3.Vector, data Data)

Merge updates the meta data with the new data.

func (*MetaData) TotalX added in v0.2.6

func (meta *MetaData) TotalX() float64

TotalX returns the totalX stored in metadata.

func (*MetaData) TotalY added in v0.2.6

func (meta *MetaData) TotalY() float64

TotalY returns the totalY stored in metadata.

func (*MetaData) TotalZ added in v0.2.6

func (meta *MetaData) TotalZ() float64

TotalZ returns the totalZ stored in metadata.

type NodeType added in v0.2.14

type NodeType uint8

NodeType represents the possible types of nodes in an octree.

type PCDType

type PCDType int

PCDType is the format of a pcd file.

const (
	// PCDAscii ascii format for pcd.
	PCDAscii PCDType = 0
	// PCDBinary binary format for pcd.
	PCDBinary PCDType = 1
	// PCDCompressed binary format for pcd.
	PCDCompressed PCDType = 2
)

type PCType

type PCType int

PCType is the type of point cloud to read the PCD file into.

const (
	// BasicType is a selector for a pointcloud backed by a BasicPointCloud.
	BasicType PCType = 0
	// KDTreeType is a selector for a pointcloud backed by a KD Tree.
	KDTreeType PCType = 1
	// BasicOctreeType is a selector for a pointcloud backed by a Basic Octree.
	BasicOctreeType PCType = 2
)

type Plane

type Plane interface {
	Equation() [4]float64                  // Returns an array of the plane equation [0]x + [1]y + [2]z + [3] = 0.
	Normal() r3.Vector                     // The normal vector of the plane, could point "up" or "down".
	Center() r3.Vector                     // The center point of the plane (the planes are not infinite).
	Offset() float64                       //  the [3] term in the equation of the plane.
	PointCloud() (PointCloud, error)       // Returns the underlying pointcloud that makes up the plane.
	Distance(p r3.Vector) float64          // The distance of a point p from the nearest point on the plane.
	Intersect(p0, p1 r3.Vector) *r3.Vector // The intersection point of the plane with line defined by p0,p1. return nil if parallel.
}

Plane defines a planar object in a 3D space.

func NewEmptyPlane

func NewEmptyPlane() Plane

NewEmptyPlane initializes an empty plane object.

func NewPlane

func NewPlane(cloud PointCloud, equation [4]float64) Plane

NewPlane creates a new plane object from a point cloud.

func NewPlaneFromVoxel

func NewPlaneFromVoxel(normal, center r3.Vector, offset float64, points map[r3.Vector]Data, voxelKeys []VoxelCoords) Plane

NewPlaneFromVoxel creats a Plane object from a set of voxel properties.

func NewPlaneWithCenter

func NewPlaneWithCenter(cloud PointCloud, equation [4]float64, center r3.Vector) Plane

NewPlaneWithCenter creates a new plane object from a point cloud.

type PointAndData

type PointAndData struct {
	P r3.Vector
	D Data
}

PointAndData is a tiny struct to facilitate returning nearest neighbors in a neat way.

type PointCloud

type PointCloud interface {
	// Size returns the number of points in the cloud.
	Size() int

	// MetaData returns meta data
	MetaData() MetaData

	// Set places the given point in the cloud.
	Set(p r3.Vector, d Data) error

	// At returns the point in the cloud at the given position.
	// The 2nd return is if the point exists, the first is data if any.
	At(x, y, z float64) (Data, bool)

	// Iterate iterates over all points in the cloud and calls the given
	// function for each point. If the supplied function returns false,
	// iteration will stop after the function returns.
	// numBatches lets you divide up he work. 0 means don't divide
	// myBatch is used iff numBatches > 0 and is which batch you want
	Iterate(numBatches, myBatch int, fn func(p r3.Vector, d Data) bool)
}

PointCloud is a general purpose container of points. It does not dictate whether or not the cloud is sparse or dense. The current basic implementation is sparse however.

func ApplyOffset added in v0.2.11

func ApplyOffset(ctx context.Context, srcpc PointCloud, pose spatialmath.Pose, logger logging.Logger) (PointCloud, error)

ApplyOffset takes a point cloud and an offset pose and applies the offset to each of the points in the source point cloud.

func MergePointClouds

func MergePointClouds(ctx context.Context, cloudFuncs []CloudAndOffsetFunc, logger logging.Logger) (PointCloud, error)

MergePointClouds takes a slice of points clouds with optional offsets and adds all their points to one point cloud.

func MergePointCloudsWithColor

func MergePointCloudsWithColor(clusters []PointCloud) (PointCloud, error)

MergePointCloudsWithColor creates a union of point clouds from the slice of point clouds, giving each element of the slice a unique color.

func New

func New() PointCloud

New returns an empty PointCloud backed by a basicPointCloud.

func NewAppendOnlyOnlyPointsPointCloud

func NewAppendOnlyOnlyPointsPointCloud(allocSize int) PointCloud

NewAppendOnlyOnlyPointsPointCloud creates a point cloud that only can be appended to and iterated. It also can't have any meta data with it.

func NewFromFile

func NewFromFile(fn string, logger logging.Logger) (PointCloud, error)

NewFromFile returns a pointcloud read in from the given file.

func NewFromLASFile

func NewFromLASFile(fn string, logger logging.Logger) (PointCloud, error)

NewFromLASFile returns a point cloud from reading a LAS file. If any lossiness of points could occur from reading it in, it's reported but is not an error.

func NewRoundingPointCloud

func NewRoundingPointCloud() PointCloud

NewRoundingPointCloud returns a new, empty, rounding PointCloud.

func NewRoundingPointCloudFromFile

func NewRoundingPointCloudFromFile(fn string, logger logging.Logger) (PointCloud, error)

NewRoundingPointCloudFromFile like NewFromFile, returns a PointCloud but rounds all points in advance.

func NewRoundingPointCloudFromPC

func NewRoundingPointCloudFromPC(pc PointCloud) (PointCloud, error)

NewRoundingPointCloudFromPC creates a rounding point cloud from any kind of input point cloud.

func NewWithPrealloc

func NewWithPrealloc(size int) PointCloud

NewWithPrealloc returns an empty, preallocated PointCloud backed by a basicPointCloud.

func PrunePointClouds

func PrunePointClouds(clouds []PointCloud, nMin int) []PointCloud

PrunePointClouds removes point clouds from a slice if the point cloud has less than nMin points.

func ReadPCD

func ReadPCD(inRaw io.Reader) (PointCloud, error)

ReadPCD reads a PCD file into a pointcloud.

func VectorsToPointCloud added in v0.2.10

func VectorsToPointCloud(vectors []r3.Vector, c color.NRGBA) (PointCloud, error)

VectorsToPointCloud converts a list of r3.Vectors into a pointcloud with the specified color.

type Vectors

type Vectors []r3.Vector

Vectors is a series of three-dimensional vectors.

func (Vectors) Len

func (vs Vectors) Len() int

Len returns the number of vectors.

func (Vectors) Less

func (vs Vectors) Less(i, j int) bool

Less returns which vector is less than the other based on r3.Vector.Cmp.

func (Vectors) Swap

func (vs Vectors) Swap(i, j int)

Swap swaps two vectors positionally.

type Voxel

type Voxel struct {
	Key             VoxelCoords
	Label           int
	Points          map[r3.Vector]Data
	Center          r3.Vector
	Normal          r3.Vector
	Offset          float64
	Residual        float64
	Weight          float64
	SortedWeightIdx int
	PointLabels     []int
}

Voxel is the structure to store data relevant to Voxel operations in point clouds.

func NewVoxel

func NewVoxel(coords VoxelCoords) *Voxel

NewVoxel creates a pointer to a Voxel struct.

func NewVoxelFromPoint

func NewVoxelFromPoint(pt, ptMin r3.Vector, voxelSize float64) *Voxel

NewVoxelFromPoint creates a new voxel from a point.

func (*Voxel) CanMerge

func (v1 *Voxel) CanMerge(v2 *Voxel, angleTh, cosTh float64) bool

CanMerge returns true if two voxels can be added to the same connected component.

func (*Voxel) ComputeCenter

func (v1 *Voxel) ComputeCenter()

ComputeCenter computer barycenter of points in voxel.

func (*Voxel) GetPlane

func (v1 *Voxel) GetPlane() Plane

GetPlane returns the plane struct with the voxel data.

func (*Voxel) IsContinuous

func (v1 *Voxel) IsContinuous(v2 *Voxel, cosTh float64) bool

IsContinuous returns true if two voxels respect the continuity constraint, false otherwise cosTh is in [0,1].

func (*Voxel) IsSmooth

func (v1 *Voxel) IsSmooth(v2 *Voxel, angleTh float64) bool

IsSmooth returns true if two voxels respect the smoothness constraint, false otherwise angleTh is expressed in degrees.

func (*Voxel) Positions

func (v1 *Voxel) Positions() []r3.Vector

Positions gets the positions of the points inside the voxel.

func (*Voxel) SetLabel

func (v1 *Voxel) SetLabel(label int)

SetLabel sets a voxel.

type VoxelCoords

type VoxelCoords struct {
	I, J, K int64
}

VoxelCoords stores Voxel coordinates in VoxelGrid axes.

func GetVoxelCoordinates

func GetVoxelCoordinates(pt, ptMin r3.Vector, voxelSize float64) VoxelCoords

GetVoxelCoordinates computes voxel coordinates in VoxelGrid Axes.

func (VoxelCoords) IsEqual

func (c VoxelCoords) IsEqual(c2 VoxelCoords) bool

IsEqual tests if two VoxelCoords are the same.

type VoxelGrid

type VoxelGrid struct {
	Voxels map[VoxelCoords]*Voxel
	// contains filtered or unexported fields
}

VoxelGrid contains the sparse grid of Voxels of a point cloud.

func NewVoxelGrid

func NewVoxelGrid(voxelSize, lam float64) *VoxelGrid

NewVoxelGrid returns a pointer to a VoxelGrid with a (0,0,0) Voxel.

func NewVoxelGridFromPointCloud

func NewVoxelGridFromPointCloud(pc PointCloud, voxelSize, lam float64) *VoxelGrid

NewVoxelGridFromPointCloud creates and fills a VoxelGrid from a point cloud.

func (*VoxelGrid) ConvertToPointCloudWithValue

func (vg *VoxelGrid) ConvertToPointCloudWithValue() (PointCloud, error)

ConvertToPointCloudWithValue converts the voxel grid to a point cloud with values are containing the labels.

func (VoxelGrid) GetAdjacentVoxels

func (vg VoxelGrid) GetAdjacentVoxels(v *Voxel) []VoxelCoords

GetAdjacentVoxels gets adjacent voxels in point cloud in 26-connectivity.

func (*VoxelGrid) GetKeysByDecreasingOrderWeights

func (vg *VoxelGrid) GetKeysByDecreasingOrderWeights() []VoxelCoords

GetKeysByDecreasingOrderWeights get the voxels keys in decreasing weight order.

func (VoxelGrid) GetNNearestVoxels

func (vg VoxelGrid) GetNNearestVoxels(v *Voxel, n uint) []VoxelCoords

GetNNearestVoxels gets voxels around a grid coordinate that are N units or less away in each dimension.

func (*VoxelGrid) GetPlanesFromLabels

func (vg *VoxelGrid) GetPlanesFromLabels() ([]Plane, PointCloud, error)

GetPlanesFromLabels returns a slice containing all the planes in the point cloud.

func (*VoxelGrid) GetUnlabeledVoxels

func (vg *VoxelGrid) GetUnlabeledVoxels() []VoxelCoords

GetUnlabeledVoxels gathers in a slice all voxels whose label is 0.

func (*VoxelGrid) GetVoxelFromKey

func (vg *VoxelGrid) GetVoxelFromKey(coords VoxelCoords) *Voxel

GetVoxelFromKey returns a pointer to a voxel from a VoxelCoords key.

func (*VoxelGrid) LabelNonPlanarVoxels

func (vg *VoxelGrid) LabelNonPlanarVoxels(unlabeledVoxels []VoxelCoords, dTh float64)

LabelNonPlanarVoxels labels potential planar parts in Voxels that are containing more than one plane if a voxel contains no plane, the minimum distance of a point to one of the surrounding plane should be above the threshold dTh.

func (*VoxelGrid) LabelVoxels

func (vg *VoxelGrid) LabelVoxels(sortedKeys []VoxelCoords, wTh, thetaTh, phiTh float64)

LabelVoxels performs voxel plane labeling If a voxel contains points from one plane, voxel propagation is done to the neighboring voxels that are also planar and share the same plane equation.

func (*VoxelGrid) Lambda

func (vg *VoxelGrid) Lambda() float64

Lambda is the clustering parameter for making voxel planes.

func (*VoxelGrid) SegmentPlanesRegionGrowing

func (vg *VoxelGrid) SegmentPlanesRegionGrowing(wTh, thetaTh, phiTh, dTh float64)

SegmentPlanesRegionGrowing segments planes in the points in the VoxelGrid This segmentation only takes into account the coordinates of the points.

func (*VoxelGrid) VoxelHistogram

func (vg *VoxelGrid) VoxelHistogram(w, h int, name string) (image.Image, error)

VoxelHistogram creates useful plots for determining the parameters of the voxel grid when calibrating a new sensor. Histograms of the number of points in each voxel, the weights of each voxel, and the plane residuals.

func (*VoxelGrid) VoxelSize

func (vg *VoxelGrid) VoxelSize() float64

VoxelSize is the side length of the voxels in the VoxelGrid.

type VoxelSlice

type VoxelSlice []*Voxel

VoxelSlice is a slice that contains Voxels.

func (VoxelSlice) Len

func (d VoxelSlice) Len() int

Len for VoxelSlice sorting interface.

func (VoxelSlice) Less

func (d VoxelSlice) Less(i, j int) bool

Less for VoxelSlice sorting interface.

func (VoxelSlice) Swap

func (d VoxelSlice) Swap(i, j int)

Swap for VoxelSlice sorting interface.

func (VoxelSlice) ToPointCloud

func (d VoxelSlice) ToPointCloud() (PointCloud, error)

ToPointCloud uses the points in the slice of voxels to create a point cloud.

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL