image_geometry

image_geometry simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.

class image_geometry.PinholeCameraModel

A pinhole camera is an idealized monocular camera.

cx()

Returns x center

cy()

Returns y center

distortionCoeffs()

Returns D

fromCameraInfo(msg)
Parameters:msg (sensor_msgs.msg.CameraInfo) – camera parameters

Set the camera parameters from the sensor_msgs.msg.CameraInfo message.

fx()

Returns x focal length

fy()

Returns y focal length

intrinsicMatrix()

Returns K, also called camera_matrix in cv docs

project3dToPixel(point)
Parameters:point ((x, y, z)) – 3D point

Returns the rectified pixel coordinates (u, v) of the 3D point, using the camera P matrix. This is the inverse of projectPixelTo3dRay().

projectPixelTo3dRay(uv)
Parameters:uv ((u, v)) – rectified pixel coordinates

Returns the unit vector which passes from the camera center to through rectified pixel (u, v), using the camera P matrix. This is the inverse of project3dToPixel().

projectionMatrix()

Returns P

rectifyImage(raw, rectified)
Parameters:
  • raw (CvMat or IplImage) – input image
  • rectified (CvMat or IplImage) – rectified output image

Applies the rectification specified by camera parameters K and and D to image raw and writes the resulting image rectified.

rectifyPoint(uv_raw)
Parameters:uv_raw ((u, v)) – pixel coordinates

Applies the rectification specified by camera parameters K and and D to point (u, v) and returns the pixel coordinates of the rectified point.

rotationMatrix()

Returns R

tfFrame()

Returns the tf frame name - a string - of the camera. This is the frame of the sensor_msgs.msg.CameraInfo message.

class image_geometry.StereoCameraModel

An idealized stereo camera.

fromCameraInfo(left_msg, right_msg)
Parameters:
  • left_msg (sensor_msgs.msg.CameraInfo) – left camera parameters
  • right_msg (sensor_msgs.msg.CameraInfo) – right camera parameters

Set the camera parameters from the sensor_msgs.msg.CameraInfo messages.

getDisparity(Z)
Parameters:Z (float) – Z (depth), in cartesian space

Returns the disparity observed for a point at depth Z. This is the inverse of getZ().

getZ(disparity)
Parameters:disparity (float) – disparity, in pixels

Returns the depth at which a point is observed with a given disparity. This is the inverse of getDisparity().

Note that a disparity of zero implies Z is infinite.

project3dToPixel(point)
Parameters:point ((x, y, z)) – 3D point

Returns the rectified pixel coordinates (u, v) of the 3D point, for each camera, as ((u_left, v_left), (u_right, v_right)) using the cameras’ P matrices. This is the inverse of projectPixelTo3d().

projectPixelTo3d(left_uv, disparity)
Parameters:
  • left_uv ((u, v)) – rectified pixel coordinates
  • disparity (float) – disparity, in pixels

Returns the 3D point (x, y, z) for the given pixel position, using the cameras’ P matrices. This is the inverse of project3dToPixel().

Note that a disparity of zero implies that the 3D point is at infinity.

tfFrame()

Returns the tf frame name - a string - of the 3d points. This is the frame of the sensor_msgs.msg.CameraInfo message. It may be used as a source frame in tf.TransformListener.

Indices and tables