image_geometry simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.
A pinhole camera is an idealized monocular camera.
Parameters: | msg (sensor_msgs.msg.CameraInfo) – camera parameters |
---|
Set the camera parameters from the sensor_msgs.msg.CameraInfo message.
Parameters: |
|
---|
Applies the rectification specified by camera parameters K and and D to image raw and writes the resulting image rectified.
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.
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().
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().
Returns D
Returns K, also called camera_matrix in cv docs
Returns P
Returns R
Returns x center
Returns y center
Returns x focal length
Returns y focal length
An idealized stereo camera.
Parameters: |
|
---|
Set the camera parameters from the sensor_msgs.msg.CameraInfo messages.
Parameters: | Z (float) – Z (depth), in cartesian space |
---|
Returns the disparity observed for a point at depth Z. This is the inverse of getZ().
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.
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().
Parameters: |
|
---|
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.
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.