transform

package
v0.26.0 Latest Latest
Warning

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

Go to latest
Published: Apr 29, 2024 License: AGPL-3.0 Imports: 22 Imported by: 9

Documentation

Overview

Package transform provides image transformation utilities relying on camera parameters.

It also understands how to work with multiple images originating from different cameras.

Index

Constants

View Source
const (
	// BrownConradyDistortionType is for simple lenses of narrow field easily modeled as a pinhole camera.
	BrownConradyDistortionType = DistortionType("brown_conrady")
	// KannalaBrandtDistortionType is for wide-angle and fisheye lense distortion.
	KannalaBrandtDistortionType = DistortionType("kannala_brandt")
)

Variables

View Source
var ErrNoIntrinsics = errors.New("camera intrinsic parameters are not available")

ErrNoIntrinsics is when a camera does not have intrinsics parameters or other parameters.

View Source
var IntelConfig = AlignConfig{
	ColorInputSize:  image.Point{1280, 720},
	ColorWarpPoints: []image.Point{{0, 0}, {1196, 720}},

	DepthInputSize:  image.Point{1024, 768},
	DepthWarpPoints: []image.Point{{67, 100}, {1019, 665}},

	OutputSize: image.Point{640, 360},
}

IntelConfig is an alignment config for some Intel camera.

Functions

func ApplyHomography

func ApplyHomography(h *Homography, pts []r2.Point) []r2.Point

ApplyHomography applies a homography on a slice of r2.Vec.

func ApplyNormalizationMat

func ApplyNormalizationMat(h *mat.Dense, pts []r2.Point) []r2.Point

ApplyNormalizationMat applies a normalization matrix to a slice of r2.Point.

func BuildExtrinsicOptProblem

func BuildExtrinsicOptProblem(conf *ExtrinsicCalibrationConfig) (*optimize.Problem, error)

BuildExtrinsicOptProblem creates the optimization problem to solve for the extrinsic matrix given the intrinsic matrices of the depth and color camera, as well as a set of corresponding points between the two cameras. depthPoints are the x,y pixels of the depth map and the measured depth at that pixel, and the colorPoints are the x,y pixels of the corresponding point in the color image.

func ComputeFundamentalMatrixAllPoints

func ComputeFundamentalMatrixAllPoints(pts1, pts2 []r2.Point, normalize bool) (*mat.Dense, error)

ComputeFundamentalMatrixAllPoints compute the fundamental matrix from all points.

func ComputeNormalizationMatFromSliceVecs

func ComputeNormalizationMatFromSliceVecs(pts []r2.Point) *mat.Dense

ComputeNormalizationMatFromSliceVecs computes the normalization matrix from a slice of vectors from Multiple View Geometry. Richard Hartley and Andrew Zisserman. Alg 4.2 p109.

func Convert2DPointsToHomogeneousPoints

func Convert2DPointsToHomogeneousPoints(pts []r2.Point) []r3.Vector

Convert2DPointsToHomogeneousPoints converts float64 image coordinates to homogeneous float64 coordinates.

func DecomposeEssentialMatrix

func DecomposeEssentialMatrix(essMat *mat.Dense) (*mat.Dense, *mat.Dense, *mat.Dense, error)

DecomposeEssentialMatrix decomposes the Essential matrix into 2 possible 3D rotations and a 3D translation.

func GetCorrectCameraPose

func GetCorrectCameraPose(poses []*mat.Dense, pts1, pts2 []r3.Vector) *mat.Dense

GetCorrectCameraPose returns the best pose, which is the pose with the most positive depth values.

func GetEssentialMatrixFromFundamental

func GetEssentialMatrixFromFundamental(k1, k2, f *mat.Dense) (*mat.Dense, error)

GetEssentialMatrixFromFundamental returns the essential matrix from the fundamental matrix and intrinsics parameters.

func GetLinearTriangulatedPoints

func GetLinearTriangulatedPoints(pose *mat.Dense, pts1, pts2 []r3.Vector) ([]r3.Vector, error)

GetLinearTriangulatedPoints computes triangulated 3D points with linear method.

func GetNumberPositiveDepth

func GetNumberPositiveDepth(pose *mat.Dense, pts1, pts2 []r3.Vector, useNonLinear bool) (int, *mat.Dense)

GetNumberPositiveDepth computes the number of positive zs in triangulated points pts1 and pts2.

func GetPossibleCameraPoses

func GetPossibleCameraPoses(essMat *mat.Dense) ([]*mat.Dense, error)

GetPossibleCameraPoses computes all 4 possible poses from the essential matrix.

func ImageAlign

func ImageAlign(
	img1Size image.Point,
	img1Points []image.Point,
	img2Size image.Point,
	img2Points []image.Point,
	logger logging.Logger,
) ([]image.Point, []image.Point, error)

ImageAlign returns points suitable for calling warp on.

func InvalidDistortionError added in v0.2.14

func InvalidDistortionError(msg string) error

InvalidDistortionError is used when the distortion_parameters are invalid.

func MeanVarianceCol

func MeanVarianceCol(m mat.Matrix, j int) (float64, float64)

MeanVarianceCol is a helper function to compute the normalization matrix for least squares homography estimation It estimates the mean and variance of a column in a *mat.Dense.

func NewNoIntrinsicsError

func NewNoIntrinsicsError(msg string) error

NewNoIntrinsicsError is used when the intriniscs are not defined.

func ProjectPointCloudToRGBPlane

func ProjectPointCloudToRGBPlane(
	pts pointcloud.PointCloud,
	h, w int,
	params PinholeCameraIntrinsics,
	pixel2meter float64,
) (pointcloud.PointCloud, error)

ProjectPointCloudToRGBPlane projects points in a pointcloud to a given camera image plane.

func RunPinholeExtrinsicCalibration

func RunPinholeExtrinsicCalibration(prob *optimize.Problem, logger logging.Logger) (spatialmath.Pose, error)

RunPinholeExtrinsicCalibration will solve the optimization problem to find the rigid pose (translation and rotation) that changes the reference frame from the point of view of the depth camera to the point of the view of the color camera.

func SelectFourPointPairs

func SelectFourPointPairs(p1, p2 []r2.Point) ([]r2.Point, []r2.Point, error)

SelectFourPointPairs randomly selects 4 pairs of points in two point slices of the same length.

Types

type AlignConfig

type AlignConfig struct {
	ColorInputSize  image.Point // this validates input size
	ColorWarpPoints []image.Point

	DepthInputSize  image.Point // this validates output size
	DepthWarpPoints []image.Point

	WarpFromCommon bool
	OutputSize     image.Point
	OutputOrigin   image.Point
}

AlignConfig TODO.

func (AlignConfig) CheckValid

func (config AlignConfig) CheckValid() error

CheckValid TODO.

func (AlignConfig) ComputeWarpFromCommon

func (config AlignConfig) ComputeWarpFromCommon(logger logging.Logger) (*AlignConfig, error)

ComputeWarpFromCommon TODO.

type Aligner added in v0.1.0

type Aligner interface {
	AlignColorAndDepthImage(*rimage.Image, *rimage.DepthMap) (*rimage.Image, *rimage.DepthMap, error)
}

Aligner aligns a color and depth image together.

type BrownConrady added in v0.1.0

type BrownConrady struct {
	RadialK1     float64 `json:"rk1"`
	RadialK2     float64 `json:"rk2"`
	RadialK3     float64 `json:"rk3"`
	TangentialP1 float64 `json:"tp1"`
	TangentialP2 float64 `json:"tp2"`
}

BrownConrady is a struct for some terms of a modified Brown-Conrady model of distortion.

func NewBrownConrady added in v0.1.0

func NewBrownConrady(inp []float64) (*BrownConrady, error)

NewBrownConrady takes in a slice of floats that will be passed into the struct in order.

func (*BrownConrady) CheckValid added in v0.2.14

func (bc *BrownConrady) CheckValid() error

CheckValid checks if the fields for BrownConrady have valid inputs.

func (*BrownConrady) ModelType added in v0.1.0

func (bc *BrownConrady) ModelType() DistortionType

ModelType returns the type of distortion model.

func (*BrownConrady) Parameters added in v0.1.0

func (bc *BrownConrady) Parameters() []float64

Parameters returns the parameters of the distortion model as a list of floats.

func (*BrownConrady) Transform added in v0.1.0

func (bc *BrownConrady) Transform(x, y float64) (float64, float64)

Transform distorts the input points x,y according to a modified Brown-Conrady model as described by OpenCV https://docs.opencv.org/3.4/da/d54/group__imgproc__transform.html#ga7dfb72c9cf9780a347fbe3d1c47e5d5a

type CamPose

type CamPose struct {
	PoseMat     *mat.Dense
	Rotation    *mat.Dense
	Translation *mat.Dense
}

CamPose stores the 3x4 pose matrix as well as the 3D Rotation and Translation matrices.

func EstimateNewPose

func EstimateNewPose(pts1, pts2 []r2.Point, k *mat.Dense) (*CamPose, error)

EstimateNewPose estimates the pose of the camera in the second set of points wrt the pose of the camera in the first set of points pts1 and pts2 are matches in 2 images (successive in time or from 2 different cameras of the same scene at the same time).

func NewCamPoseFromMat

func NewCamPoseFromMat(pose *mat.Dense) *CamPose

NewCamPoseFromMat creates a pointer to a Camera pose from a 4x3 pose dense matrix.

func (*CamPose) Pose

func (cp *CamPose) Pose() (spatialmath.Pose, error)

Pose creates a spatialmath.Pose from a CamPose.

type CameraSystem added in v0.1.0

type CameraSystem interface {
	Projector
	Distorter
}

A CameraSystem stores the system of camera models, the intrinsic parameters of each camera, and the distortion model.

type DepthColorHomography

type DepthColorHomography struct {
	Homography   *Homography `json:"transform"`
	DepthToColor bool        `json:"depth_to_color"`
	RotateDepth  int         `json:"rotate_depth_degs"`
}

DepthColorHomography stores the color camera intrinsics and the homography that aligns a depth map with the color image. DepthToColor is true if the homography maps from depth pixels to color pixels, and false if it maps from color pixels to depth pixels. These parameters can take the color and depth image and create a point cloud of 3D points where the origin is the origin of the color camera, with units of mm.

func NewDepthColorHomography

func NewDepthColorHomography(inp *RawDepthColorHomography) (*DepthColorHomography, error)

NewDepthColorHomography takes in a struct that stores raw data from JSON and converts it into a DepthColorHomography struct.

func (*DepthColorHomography) AlignColorAndDepthImage

func (dch *DepthColorHomography) AlignColorAndDepthImage(col *rimage.Image, dep *rimage.DepthMap,
) (*rimage.Image, *rimage.DepthMap, error)

AlignColorAndDepthImage will take the depth and the color image and overlay the two properly by transforming the depth map to the color map.

type DepthColorIntrinsicsExtrinsics

type DepthColorIntrinsicsExtrinsics struct {
	ColorCamera  PinholeCameraIntrinsics
	DepthCamera  PinholeCameraIntrinsics
	ExtrinsicD2C spatialmath.Pose
}

DepthColorIntrinsicsExtrinsics holds the intrinsics for a color camera, a depth camera, and the pose transformation that transforms a point from being in the reference frame of the depth camera to the reference frame of the color camera.

func NewDepthColorIntrinsicsExtrinsicsFromBytes

func NewDepthColorIntrinsicsExtrinsicsFromBytes(byteJSON []byte) (*DepthColorIntrinsicsExtrinsics, error)

NewDepthColorIntrinsicsExtrinsicsFromBytes reads a JSON byte stream and turns it into DepthColorIntrinsicsExtrinsics.

func NewDepthColorIntrinsicsExtrinsicsFromJSONFile

func NewDepthColorIntrinsicsExtrinsicsFromJSONFile(jsonPath string) (*DepthColorIntrinsicsExtrinsics, error)

NewDepthColorIntrinsicsExtrinsicsFromJSONFile takes in a file path to a JSON and turns it into DepthColorIntrinsicsExtrinsics.

func NewEmptyDepthColorIntrinsicsExtrinsics

func NewEmptyDepthColorIntrinsicsExtrinsics() *DepthColorIntrinsicsExtrinsics

NewEmptyDepthColorIntrinsicsExtrinsics creates an zero initialized DepthColorIntrinsicsExtrinsics.

func (*DepthColorIntrinsicsExtrinsics) AlignColorAndDepthImage

func (dcie *DepthColorIntrinsicsExtrinsics) AlignColorAndDepthImage(c *rimage.Image, d *rimage.DepthMap,
) (*rimage.Image, *rimage.DepthMap, error)

AlignColorAndDepthImage takes in a RGB image and Depth map and aligns them according to the Aligner, returning a new Image and DepthMap.

func (*DepthColorIntrinsicsExtrinsics) ApplyRigidBodyTransform added in v0.1.0

func (dcie *DepthColorIntrinsicsExtrinsics) ApplyRigidBodyTransform(pts pointcloud.PointCloud) (pointcloud.PointCloud, error)

ApplyRigidBodyTransform projects a 3D point in a given camera image plane and return a new point cloud leaving the original unchanged.

func (*DepthColorIntrinsicsExtrinsics) CheckValid

func (dcie *DepthColorIntrinsicsExtrinsics) CheckValid() error

CheckValid checks if the fields for DepthColorIntrinsicsExtrinsics have valid inputs.

func (*DepthColorIntrinsicsExtrinsics) DepthPixelToColorPixel

func (dcie *DepthColorIntrinsicsExtrinsics) DepthPixelToColorPixel(dx, dy, dz float64) (float64, float64, float64)

DepthPixelToColorPixel takes a pixel+depth (x,y, depth) from the depth camera and output is the coordinates of the color camera. Extrinsic matrices in meters, points are in mm, need to convert to m and then back.

func (*DepthColorIntrinsicsExtrinsics) ImagePointTo3DPoint

func (dcie *DepthColorIntrinsicsExtrinsics) ImagePointTo3DPoint(point image.Point, depth rimage.Depth) (r3.Vector, error)

ImagePointTo3DPoint takes in a image coordinate and returns the 3D point from the camera matrix.

func (*DepthColorIntrinsicsExtrinsics) PointCloudToRGBD

func (dcie *DepthColorIntrinsicsExtrinsics) PointCloudToRGBD(
	cloud pointcloud.PointCloud,
) (*rimage.Image, *rimage.DepthMap, error)

PointCloudToRGBD takes a PointCloud with color info and returns an Image and DepthMap from the perspective of the color camera referenceframe.

func (*DepthColorIntrinsicsExtrinsics) RGBDToPointCloud

func (dcie *DepthColorIntrinsicsExtrinsics) RGBDToPointCloud(
	img *rimage.Image, dm *rimage.DepthMap,
	crop ...image.Rectangle,
) (pointcloud.PointCloud, error)

RGBDToPointCloud takes an Image and DepthMap and uses the camera parameters to project it to a pointcloud.

func (*DepthColorIntrinsicsExtrinsics) TransformDepthCoordToColorCoord

func (dcie *DepthColorIntrinsicsExtrinsics) TransformDepthCoordToColorCoord(
	col *rimage.Image, dep *rimage.DepthMap,
) (*rimage.Image, *rimage.DepthMap, error)

TransformDepthCoordToColorCoord changes the coordinate system of the depth map to be in same coordinate system as the color image.

func (*DepthColorIntrinsicsExtrinsics) TransformPointToPoint added in v0.1.0

func (dcie *DepthColorIntrinsicsExtrinsics) TransformPointToPoint(x, y, z float64) (float64, float64, float64)

TransformPointToPoint applies a rigid body transform specified as a Pose to two points.

type DepthColorIntrinsicsExtrinsicsConfig added in v0.1.0

type DepthColorIntrinsicsExtrinsicsConfig struct {
	ColorCamera  PinholeCameraIntrinsics `json:"color_intrinsic_parameters"`
	DepthCamera  PinholeCameraIntrinsics `json:"depth_intrinsic_parameters"`
	ExtrinsicD2C json.RawMessage         `json:"depth_to_color_extrinsic_parameters"`
}

DepthColorIntrinsicsExtrinsicsConfig is the config file that will be parsed into the proper interface.

type DepthColorWarpTransforms

type DepthColorWarpTransforms struct {
	ColorTransform, DepthTransform rimage.TransformationMatrix
	*AlignConfig                   // anonymous fields
}

DepthColorWarpTransforms TODO.

func NewDepthColorWarpTransforms

func NewDepthColorWarpTransforms(config *AlignConfig, logger logging.Logger) (*DepthColorWarpTransforms, error)

NewDepthColorWarpTransforms TODO.

func (*DepthColorWarpTransforms) AlignColorAndDepthImage

func (dct *DepthColorWarpTransforms) AlignColorAndDepthImage(col *rimage.Image, dep *rimage.DepthMap,
) (*rimage.Image, *rimage.DepthMap, error)

AlignColorAndDepthImage will warp the color and depth map in order to have them aligned on top of each other.

func (*DepthColorWarpTransforms) ImagePointTo3DPoint

func (dct *DepthColorWarpTransforms) ImagePointTo3DPoint(point image.Point, d rimage.Depth) (r3.Vector, error)

ImagePointTo3DPoint takes in a image coordinate and returns the 3D point from the warp points.

func (*DepthColorWarpTransforms) PointCloudToRGBD

func (dct *DepthColorWarpTransforms) PointCloudToRGBD(
	cloud pointcloud.PointCloud,
) (*rimage.Image, *rimage.DepthMap, error)

PointCloudToRGBD takes a PointCloud with color info and returns an Image and DepthMap from the perspective of the color camera referenceframe.

func (*DepthColorWarpTransforms) RGBDToPointCloud

func (dct *DepthColorWarpTransforms) RGBDToPointCloud(
	img *rimage.Image, dm *rimage.DepthMap,
	crop ...image.Rectangle,
) (pointcloud.PointCloud, error)

RGBDToPointCloud transforms an already aligned Image and DepthMap into a PointCloud.

type Distorter added in v0.1.0

type Distorter interface {
	ModelType() DistortionType
	CheckValid() error
	Parameters() []float64
	Transform(x, y float64) (float64, float64)
}

Distorter defines a Transform that takes an undistorted image and distorts it according to the model.

func NewDistorter added in v0.1.0

func NewDistorter(distortionType DistortionType, parameters []float64) (Distorter, error)

NewDistorter returns a Distorter given a valid DistortionType and its parameters.

type DistortionType added in v0.1.0

type DistortionType string

DistortionType is the name of the distortion model.

type ExtrinsicCalibrationConfig

type ExtrinsicCalibrationConfig struct {
	ColorPoints     []r2.Point              `json:"color_points"`
	DepthPoints     []r3.Vector             `json:"depth_points"`
	ColorIntrinsics PinholeCameraIntrinsics `json:"color_intrinsic_parameters"`
	DepthIntrinsics PinholeCameraIntrinsics `json:"depth_intrinsic_parameters"`
}

ExtrinsicCalibrationConfig stores all the necessary parameters to do an extrinsic calibration.

type Homography

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

Homography is a 3x3 matrix used to transform a plane from the perspective of a 2D camera to the perspective of another 2D camera.

func EstimateExactHomographyFrom8Points

func EstimateExactHomographyFrom8Points(s1, s2 []r2.Point, normalize bool) (*Homography, error)

EstimateExactHomographyFrom8Points computes the exact homography from 2 sets of 4 matching points from Multiple View Geometry. Richard Hartley and Andrew Zisserman. Alg 4.1 p91.

func EstimateHomographyRANSAC

func EstimateHomographyRANSAC(pts1, pts2 []r2.Point, thresh float64, nMaxIteration int) (*Homography, []int, error)

EstimateHomographyRANSAC estimates a homography from matches of 2 sets of points with the RANdom SAmple Consensus method from Multiple View Geometry. Richard Hartley and Andrew Zisserman. Alg 4.4 p118.

func EstimateLeastSquaresHomography

func EstimateLeastSquaresHomography(pts1, pts2 *mat.Dense) (*Homography, error)

EstimateLeastSquaresHomography estimates an homography from 2 sets of corresponding points.

func NewHomography

func NewHomography(vals []float64) (*Homography, error)

NewHomography creates a Homography from a slice of floats.

func (*Homography) Apply

func (h *Homography) Apply(pt r2.Point) r2.Point

Apply will transform the given point according to the homography.

func (*Homography) At

func (h *Homography) At(row, col int) float64

At returns the value of the homography at the given index.

func (*Homography) Inverse

func (h *Homography) Inverse() (*Homography, error)

Inverse inverts the homography. If homography went from color -> depth, Inverse makes it point from depth -> color.

type ParallelProjection added in v0.1.0

type ParallelProjection struct{}

ParallelProjection to pointclouds are done in a naive way that don't take any camera parameters into account. These are not great projections, and should really only be used for testing or artistic purposes.

func (*ParallelProjection) ImagePointTo3DPoint added in v0.1.0

func (pp *ParallelProjection) ImagePointTo3DPoint(pt image.Point, d rimage.Depth) (r3.Vector, error)

ImagePointTo3DPoint takes the 2D pixel point and assumes that it represents the X,Y coordinate in mm as well.

func (*ParallelProjection) PointCloudToRGBD added in v0.1.0

func (pp *ParallelProjection) PointCloudToRGBD(cloud pointcloud.PointCloud) (*rimage.Image, *rimage.DepthMap, error)

PointCloudToRGBD assumes the x,y coordinates are the same as the x,y pixels.

func (*ParallelProjection) RGBDToPointCloud added in v0.1.0

func (pp *ParallelProjection) RGBDToPointCloud(
	img *rimage.Image,
	dm *rimage.DepthMap,
	crop ...image.Rectangle,
) (pointcloud.PointCloud, error)

RGBDToPointCloud take a 2D image with depth and project to a 3D point cloud.

type PinholeCameraIntrinsics

type PinholeCameraIntrinsics struct {
	Width  int     `json:"width_px"`
	Height int     `json:"height_px"`
	Fx     float64 `json:"fx"`
	Fy     float64 `json:"fy"`
	Ppx    float64 `json:"ppx"`
	Ppy    float64 `json:"ppy"`
}

PinholeCameraIntrinsics holds the parameters necessary to do a perspective projection of a 3D scene to the 2D plane.

func NewPinholeCameraIntrinsicsFromJSONFile

func NewPinholeCameraIntrinsicsFromJSONFile(jsonPath string) (*PinholeCameraIntrinsics, error)

NewPinholeCameraIntrinsicsFromJSONFile takes in a file path to a JSON and turns it into PinholeCameraIntrinsics.

func (*PinholeCameraIntrinsics) CheckValid

func (params *PinholeCameraIntrinsics) CheckValid() error

CheckValid checks if the fields for PinholeCameraIntrinsics have valid inputs.

func (*PinholeCameraIntrinsics) GetCameraMatrix

func (params *PinholeCameraIntrinsics) GetCameraMatrix() *mat.Dense

GetCameraMatrix creates a new camera matrix and returns it. Camera matrix: [[fx 0 ppx],

[0 fy ppy],
[0 0  1]]

func (*PinholeCameraIntrinsics) ImagePointTo3DPoint

func (params *PinholeCameraIntrinsics) ImagePointTo3DPoint(point image.Point, d rimage.Depth) (r3.Vector, error)

ImagePointTo3DPoint takes in a image coordinate and returns the 3D point from the camera matrix.

func (*PinholeCameraIntrinsics) PixelToPoint

func (params *PinholeCameraIntrinsics) PixelToPoint(x, y, z float64) (float64, float64, float64)

PixelToPoint transforms a pixel with depth to a 3D point cloud. The intrinsics parameters should be the ones of the sensor used to obtain the image that contains the pixel.

func (*PinholeCameraIntrinsics) PointCloudToRGBD

func (params *PinholeCameraIntrinsics) PointCloudToRGBD(
	cloud pointcloud.PointCloud,
) (*rimage.Image, *rimage.DepthMap, error)

PointCloudToRGBD takes a PointCloud with color info and returns an Image and DepthMap from the perspective of the camera referenceframe.

func (*PinholeCameraIntrinsics) PointToPixel

func (params *PinholeCameraIntrinsics) PointToPixel(x, y, z float64) (float64, float64)

PointToPixel projects a 3D point to a pixel in an image plane. The intrinsics parameters should be the ones of the sensor we want to project to.

func (*PinholeCameraIntrinsics) RGBDToPointCloud

func (params *PinholeCameraIntrinsics) RGBDToPointCloud(
	img *rimage.Image, dm *rimage.DepthMap,
	crop ...image.Rectangle,
) (pointcloud.PointCloud, error)

RGBDToPointCloud takes an Image and Depth map and uses the camera parameters to project it to a pointcloud.

type PinholeCameraModel added in v0.1.0

type PinholeCameraModel struct {
	*PinholeCameraIntrinsics `json:"intrinsic_parameters"`
	Distortion               Distorter `json:"distortion"`
}

PinholeCameraModel is the model of a pinhole camera.

func (*PinholeCameraModel) DistortionMap added in v0.1.0

func (params *PinholeCameraModel) DistortionMap() func(u, v float64) (float64, float64)

DistortionMap is a function that transforms the undistorted input points (u,v) to the distorted points (x,y) according to the model in PinholeCameraModel.Distortion.

func (*PinholeCameraModel) UndistortDepthMap added in v0.1.0

func (params *PinholeCameraModel) UndistortDepthMap(dm *rimage.DepthMap) (*rimage.DepthMap, error)

UndistortDepthMap takes an input depth map and creates a new depth map the same size with the same camera parameters as the original depth map, but undistorted according to the distortion model in PinholeCameraModel. A nearest neighbor interpolation is used to interpolate values between depth pixels. NOTE(bh): potentially a use case for generics

func (*PinholeCameraModel) UndistortImage added in v0.1.0

func (params *PinholeCameraModel) UndistortImage(img *rimage.Image) (*rimage.Image, error)

UndistortImage takes an input image and creates a new image the same size with the same camera parameters as the original image, but undistorted according to the distortion model in PinholeCameraModel. A bilinear interpolation is used to interpolate values between image pixels. NOTE(bh): potentially a use case for generics

type Projector added in v0.1.0

type Projector interface {
	// Project a 2D RGBD image to 3D pointcloud. Can add an optional crop to the image before projection.
	RGBDToPointCloud(*rimage.Image, *rimage.DepthMap, ...image.Rectangle) (pointcloud.PointCloud, error)
	// Project a 3D pointcloud to a 2D RGBD image.
	PointCloudToRGBD(pointcloud.PointCloud) (*rimage.Image, *rimage.DepthMap, error)
	// Project a single pixel point to a given depth.
	ImagePointTo3DPoint(image.Point, rimage.Depth) (r3.Vector, error)
}

Projector can transform a scene between a 2D Image and DepthMap and a 3D pointcloud.

type RawDepthColorHomography

type RawDepthColorHomography struct {
	Homography   []float64 `json:"transform"`
	DepthToColor bool      `json:"depth_to_color"`
	RotateDepth  int       `json:"rotate_depth_degs"`
}

RawDepthColorHomography is a structure that can be easily serialized and unserialized into JSON.

func (*RawDepthColorHomography) CheckValid

func (rdch *RawDepthColorHomography) CheckValid() error

CheckValid runs checks on the fields of the struct to see if the inputs are valid.

Directories

Path Synopsis
cmd
depth_to_color
Get the coordinates of a depth pixel in the depth map in the reference frame of the color image $./depth_to_color -conf=/path/to/intrinsics/extrinsic/file X Y Z
Get the coordinates of a depth pixel in the depth map in the reference frame of the color image $./depth_to_color -conf=/path/to/intrinsics/extrinsic/file X Y Z
extrinsic_calibration
Given at least 4 corresponding points, and the intrinsic matrices of both cameras, computes the rigid transform (rotation + translation) that would be the extrinsic transformation from camera 1 to camera 2.
Given at least 4 corresponding points, and the intrinsic matrices of both cameras, computes the rigid transform (rotation + translation) that would be the extrinsic transformation from camera 1 to camera 2.

Jump to

Keyboard shortcuts

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