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 ¶
- Variables
- func ApplyHomography(h *Homography, pts []r2.Point) []r2.Point
- func ApplyNormalizationMat(h *mat.Dense, pts []r2.Point) []r2.Point
- func ApplyRigidBodyTransform(pts pointcloud.PointCloud, params *Extrinsics) (pointcloud.PointCloud, error)
- func BuildExtrinsicOptProblem(conf *ExtrinsicCalibrationConfig) (*optimize.Problem, error)
- func ComputeFundamentalMatrixAllPoints(pts1, pts2 []r2.Point, normalize bool) (*mat.Dense, error)
- func ComputeNormalizationMatFromSliceVecs(pts []r2.Point) *mat.Dense
- func Convert2DPointsToHomogeneousPoints(pts []r2.Point) []r3.Vector
- func DecomposeEssentialMatrix(essMat *mat.Dense) (*mat.Dense, *mat.Dense, *mat.Dense, error)
- func DepthMapToPointCloud(depthImage *rimage.DepthMap, pixel2meter float64, ...) (pointcloud.PointCloud, error)
- func GetCorrectCameraPose(poses []*mat.Dense, pts1, pts2 []r3.Vector) *mat.Dense
- func GetEssentialMatrixFromFundamental(k1, k2, f *mat.Dense) (*mat.Dense, error)
- func GetLinearTriangulatedPoints(pose *mat.Dense, pts1, pts2 []r3.Vector) ([]r3.Vector, error)
- func GetNumberPositiveDepth(pose *mat.Dense, pts1, pts2 []r3.Vector, useNonLinear bool) (int, *mat.Dense)
- func GetPossibleCameraPoses(essMat *mat.Dense) ([]*mat.Dense, error)
- func ImageAlign(img1Size image.Point, img1Points []image.Point, img2Size image.Point, ...) ([]image.Point, []image.Point, error)
- func MeanVarianceCol(m mat.Matrix, j int) (float64, float64)
- func NewNoIntrinsicsError(msg string) error
- func ProjectPointCloudToRGBPlane(pts pointcloud.PointCloud, h, w int, params PinholeCameraIntrinsics, ...) (pointcloud.PointCloud, error)
- func RunPinholeExtrinsicCalibration(prob *optimize.Problem, logger golog.Logger) (spatialmath.Pose, error)
- func SelectFourPointPairs(p1, p2 []r2.Point) ([]r2.Point, []r2.Point, error)
- type AlignConfig
- type CamPose
- type DepthColorHomography
- type DepthColorIntrinsicsExtrinsics
- func (dcie *DepthColorIntrinsicsExtrinsics) AlignColorAndDepthImage(c *rimage.Image, d *rimage.DepthMap) (*rimage.Image, *rimage.DepthMap, error)
- func (dcie *DepthColorIntrinsicsExtrinsics) CheckValid() error
- func (dcie *DepthColorIntrinsicsExtrinsics) DepthPixelToColorPixel(dx, dy, dz float64) (float64, float64, float64)
- func (dcie *DepthColorIntrinsicsExtrinsics) ImagePointTo3DPoint(point image.Point, depth rimage.Depth) (r3.Vector, error)
- func (dcie *DepthColorIntrinsicsExtrinsics) PointCloudToRGBD(cloud pointcloud.PointCloud) (*rimage.Image, *rimage.DepthMap, error)
- func (dcie *DepthColorIntrinsicsExtrinsics) RGBDToPointCloud(img *rimage.Image, dm *rimage.DepthMap, crop ...image.Rectangle) (pointcloud.PointCloud, error)
- func (dcie *DepthColorIntrinsicsExtrinsics) TransformDepthCoordToColorCoord(col *rimage.Image, dep *rimage.DepthMap) (*rimage.Image, *rimage.DepthMap, error)
- type DepthColorWarpTransforms
- func (dct *DepthColorWarpTransforms) AlignColorAndDepthImage(col *rimage.Image, dep *rimage.DepthMap) (*rimage.Image, *rimage.DepthMap, error)
- func (dct *DepthColorWarpTransforms) ImagePointTo3DPoint(point image.Point, d rimage.Depth) (r3.Vector, error)
- func (dct *DepthColorWarpTransforms) PointCloudToRGBD(cloud pointcloud.PointCloud) (*rimage.Image, *rimage.DepthMap, error)
- func (dct *DepthColorWarpTransforms) RGBDToPointCloud(img *rimage.Image, dm *rimage.DepthMap, crop ...image.Rectangle) (pointcloud.PointCloud, error)
- type DistortionModel
- type ExtrinsicCalibrationConfig
- type Extrinsics
- type Homography
- func EstimateExactHomographyFrom8Points(s1, s2 []r2.Point, normalize bool) (*Homography, error)
- func EstimateHomographyRANSAC(pts1, pts2 []r2.Point, thresh float64, nMaxIteration int) (*Homography, []int, error)
- func EstimateLeastSquaresHomography(pts1, pts2 *mat.Dense) (*Homography, error)
- func NewHomography(vals []float64) (*Homography, error)
- type PinholeCameraIntrinsics
- func (params *PinholeCameraIntrinsics) CheckValid() error
- func (params *PinholeCameraIntrinsics) DistortionMap() func(u, v float64) (float64, float64)
- func (params *PinholeCameraIntrinsics) GetCameraMatrix() *mat.Dense
- func (params *PinholeCameraIntrinsics) ImagePointTo3DPoint(point image.Point, d rimage.Depth) (r3.Vector, error)
- func (params *PinholeCameraIntrinsics) PixelToPoint(x, y, z float64) (float64, float64, float64)
- func (params *PinholeCameraIntrinsics) PointCloudToRGBD(cloud pointcloud.PointCloud) (*rimage.Image, *rimage.DepthMap, error)
- func (params *PinholeCameraIntrinsics) PointToPixel(x, y, z float64) (float64, float64)
- func (params *PinholeCameraIntrinsics) RGBDToPointCloud(img *rimage.Image, dm *rimage.DepthMap, crop ...image.Rectangle) (pointcloud.PointCloud, error)
- func (params *PinholeCameraIntrinsics) UndistortDepthMap(dm *rimage.DepthMap) (*rimage.DepthMap, error)
- func (params *PinholeCameraIntrinsics) UndistortImage(img *rimage.Image) (*rimage.Image, error)
- type RawDepthColorHomography
Constants ¶
This section is empty.
Variables ¶
var ErrNoIntrinsics = errors.New("camera intrinsic parameters are not available")
ErrNoIntrinsics is when a camera does not have intrinsics parameters or other parameters.
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 ¶
ApplyNormalizationMat applies a normalization matrix to a slice of r2.Point.
func ApplyRigidBodyTransform ¶
func ApplyRigidBodyTransform(pts pointcloud.PointCloud, params *Extrinsics) (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 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 ¶
ComputeFundamentalMatrixAllPoints compute the fundamental matrix from all points.
func ComputeNormalizationMatFromSliceVecs ¶
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 ¶
Convert2DPointsToHomogeneousPoints converts float64 image coordinates to homogeneous float64 coordinates.
func DecomposeEssentialMatrix ¶
DecomposeEssentialMatrix decomposes the Essential matrix into 2 possible 3D rotations and a 3D translation.
func DepthMapToPointCloud ¶
func DepthMapToPointCloud( depthImage *rimage.DepthMap, pixel2meter float64, params *PinholeCameraIntrinsics, depthMin, depthMax rimage.Depth, ) (pointcloud.PointCloud, error)
DepthMapToPointCloud converts a Depth Map to a PointCloud using the depth camera parameters.
func GetCorrectCameraPose ¶
GetCorrectCameraPose returns the best pose, which is the pose with the most positive depth values.
func GetEssentialMatrixFromFundamental ¶
GetEssentialMatrixFromFundamental returns the essential matrix from the fundamental matrix and intrinsics parameters.
func GetLinearTriangulatedPoints ¶
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 ¶
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 golog.Logger, ) ([]image.Point, []image.Point, error)
ImageAlign returns points suitable for calling warp on.
func MeanVarianceCol ¶
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 ¶
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 golog.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.
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) ComputeWarpFromCommon ¶
func (config AlignConfig) ComputeWarpFromCommon(logger golog.Logger) (*AlignConfig, error)
ComputeWarpFromCommon TODO.
type CamPose ¶
CamPose stores the 3x4 pose matrix as well as the 3D Rotation and Translation matrices.
func EstimateNewPose ¶
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 ¶
NewCamPoseFromMat creates a pointer to a Camera pose from a 4x3 pose dense matrix.
type DepthColorHomography ¶
type DepthColorHomography struct { Homography *Homography `json:"transform"` DepthToColor bool `json:"depth_to_color"` RotateDepth int `json:"rotate_depth"` }
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 `json:"color"` DepthCamera PinholeCameraIntrinsics `json:"depth"` ExtrinsicD2C Extrinsics `json:"extrinsics_depth_to_color"` }
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) 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.
type DepthColorWarpTransforms ¶
type DepthColorWarpTransforms struct {
ColorTransform, DepthTransform rimage.TransformationMatrix
*AlignConfig // anonymous fields
}
DepthColorWarpTransforms TODO.
func NewDepthColorWarpTransforms ¶
func NewDepthColorWarpTransforms(config *AlignConfig, logger golog.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 DistortionModel ¶
type DistortionModel struct { RadialK1 float64 `json:"rk1"` RadialK2 float64 `json:"rk2"` RadialK3 float64 `json:"rk3"` TangentialP1 float64 `json:"tp1"` TangentialP2 float64 `json:"tp2"` }
DistortionModel is a struct for some terms of a modified Brown-Conrady model of distortion.
func (*DistortionModel) Transform ¶
func (dm *DistortionModel) 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 ExtrinsicCalibrationConfig ¶
type ExtrinsicCalibrationConfig struct { ColorPoints []r2.Point `json:"color_points"` DepthPoints []r3.Vector `json:"depth_points"` ColorIntrinsics PinholeCameraIntrinsics `json:"color_intrinsics"` DepthIntrinsics PinholeCameraIntrinsics `json:"depth_intrinsics"` }
ExtrinsicCalibrationConfig stores all the necessary parameters to do an extrinsic calibration.
type Extrinsics ¶
type Extrinsics struct { RotationMatrix []float64 `json:"rotation"` TranslationVector []float64 `json:"translation"` }
Extrinsics holds the rotation matrix and the translation vector necessary to transform from the camera's origin to another reference frame.
func (*Extrinsics) TransformPointToPoint ¶
func (params *Extrinsics) TransformPointToPoint(x, y, z float64) (float64, float64, float64)
TransformPointToPoint applies a rigid body transform between two cameras to a 3D point.
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 PinholeCameraIntrinsics ¶
type PinholeCameraIntrinsics struct { Width int `json:"width"` Height int `json:"height"` Fx float64 `json:"fx"` Fy float64 `json:"fy"` Ppx float64 `json:"ppx"` Ppy float64 `json:"ppy"` Distortion DistortionModel `json:"distortion"` }
PinholeCameraIntrinsics holds the parameters necessary to do a perspective projection of a 3D scene to the 2D plane, as well as the DistortionModel necessary to do corrections.
func NewPinholeCameraIntrinsicsFromJSONFile ¶
func NewPinholeCameraIntrinsicsFromJSONFile(jsonPath, cameraName 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) DistortionMap ¶
func (params *PinholeCameraIntrinsics) 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 PinholeCameraIntrinsics.Distortion.
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.
func (*PinholeCameraIntrinsics) UndistortDepthMap ¶
func (params *PinholeCameraIntrinsics) 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 PinholeCameraIntrinsics. A nearest neighbor interpolation is used to interpolate values between depth pixels. NOTE(bh): potentially a use case for generics
func (*PinholeCameraIntrinsics) UndistortImage ¶
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 PinholeCameraIntrinsics. A bilinear interpolation is used to interpolate values between image pixels. NOTE(bh): potentially a use case for generics
type RawDepthColorHomography ¶
type RawDepthColorHomography struct { Homography []float64 `json:"transform"` DepthToColor bool `json:"depth_to_color"` RotateDepth int `json:"rotate_depth"` }
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.
Source Files ¶
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. |