Class CameraInfoMessage
This message defines meta information for a camera. It should be in a camera namespace on topic "camera_info" and accompanied by up to five image topics named:
image_raw - raw data from the camera driver, possibly Bayer encoded image - monochrome, distorted image_color - color, distorted image_rect - monochrome, rectified image_rect_color - color, rectified
The image_pipeline contains packages (image_proc, stereo_image_proc) for producing the four processed image topics from image_raw and camera_info. The meaning of the camera parameters are described in detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
The image_geometry package provides a user-friendly interface to common operations using this meta information. If you want to, e.g., project a 3d point into image coordinates, we strongly recommend using image_geometry.
/// If the camera is uncalibrated, the matrices D, K, R, P should be left
zeroed out. In particular, clients may assume that K[0] == 0.0
indicates an uncalibrated camera.
Inheritance
Implements
Inherited Members
Namespace: ZO.ROS.MessageTypes.Sensor
Assembly: Unity.ZeroSim.dll
Syntax
public class CameraInfoMessage : ZOROSMessageInterface
Constructors
| Improve this Doc View SourceCameraInfoMessage()
Declaration
public CameraInfoMessage()
CameraInfoMessage(HeaderMessage, UInt32, UInt32, String, Double[], Double[], Double[], Double[], UInt32, UInt32, RegionOfInterestMessage)
Declaration
public CameraInfoMessage(HeaderMessage header, uint height, uint width, string distortion_model, double[] D, double[] K, double[] R, double[] P, uint binning_x, uint binning_y, RegionOfInterestMessage roi)
Parameters
Type | Name | Description |
---|---|---|
HeaderMessage | header | |
System.UInt32 | height | |
System.UInt32 | width | |
System.String | distortion_model | |
System.Double[] | D | |
System.Double[] | K | |
System.Double[] | R | |
System.Double[] | P | |
System.UInt32 | binning_x | |
System.UInt32 | binning_y | |
RegionOfInterestMessage | roi |
Properties
| Improve this Doc View Sourcebinning_x
Binning refers here to any camera setting which combines rectangular neighborhoods of pixels into larger "super-pixels." It reduces the resolution of the output image to (width / binning_x) x (height / binning_y). The default values binning_x = binning_y = 0 is considered the same as binning_x = binning_y = 1 (no subsampling).
Declaration
public uint binning_x { get; set; }
Property Value
Type | Description |
---|---|
System.UInt32 |
binning_y
Declaration
public uint binning_y { get; set; }
Property Value
Type | Description |
---|---|
System.UInt32 |
D
The distortion parameters, size depending on the distortion model. For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
Declaration
public double[] D { get; set; }
Property Value
Type | Description |
---|---|
System.Double[] |
distortion_model
The distortion model used. Supported models are listed in sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a simple model of radial and tangential distortion - is sufficient.
Declaration
public string distortion_model { get; set; }
Property Value
Type | Description |
---|---|
System.String |
header
Time of image acquisition, camera coordinate frame ID Header timestamp should be acquisition time of image Header frame_id should be optical frame of camera origin of frame should be optical center of camera +x should point to the right in the image +y should point down in the image +z should point into the plane of the image
Declaration
public HeaderMessage header { get; set; }
Property Value
Type | Description |
---|---|
HeaderMessage |
height
The image dimensions with which the camera was calibrated. Normally this will be the full camera resolution in pixels.
Declaration
public uint height { get; set; }
Property Value
Type | Description |
---|---|
System.UInt32 |
K
Intrinsic camera matrix for the raw (distorted) images. [fx 0 cx] K = [ 0 fy cy] [ 0 0 1] Projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx, fy) and principal point (cx, cy).
Declaration
public double[] K { get; set; }
Property Value
Type | Description |
---|---|
System.Double[] |
MessageType
Declaration
[JsonIgnore]
public string MessageType { get; }
Property Value
Type | Description |
---|---|
System.String |
P
Projection/camera matrix [fx' 0 cx' Tx] P = [ 0 fy' cy' Ty] [ 0 0 1 0] By convention, this matrix specifies the intrinsic (camera) matrix of the processed (rectified) image. That is, the left 3x3 portion is the normal camera intrinsic matrix for the rectified image. It projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx', fy') and principal point (cx', cy') - these may differ from the values in K. For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will also have R = the identity and P[1:3,1:3] = K. For a stereo pair, the fourth column [Tx Ty 0]' is related to the position of the optical center of the second camera in the first camera's frame. We assume Tz = 0 so both cameras are in the same stereo image plane. The first camera always has Tx = Ty = 0. For the right (second) camera of a horizontal stereo pair, Ty = 0 and Tx = -fx' * B, where B is the baseline between the cameras. Given a 3D point [X Y Z]', the projection (x, y) of the point onto the rectified image is given by: [u v w]' = P * [X Y Z 1]' x = u / w y = v / w This holds for both images of a stereo pair.
3x4 row-major matrix
Declaration
public double[] P { get; set; }
Property Value
Type | Description |
---|---|
System.Double[] |
R
Rectification matrix (stereo cameras only) A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel.
Declaration
public double[] R { get; set; }
Property Value
Type | Description |
---|---|
System.Double[] |
roi
Declaration
public RegionOfInterestMessage roi { get; set; }
Property Value
Type | Description |
---|---|
RegionOfInterestMessage |
Type
Declaration
[JsonIgnore]
public static string Type { get; }
Property Value
Type | Description |
---|---|
System.String |
width
Declaration
public uint width { get; set; }
Property Value
Type | Description |
---|---|
System.UInt32 |
Methods
| Improve this Doc View SourceBuildCameraInfo(UInt32, UInt32, Double)
Declaration
public void BuildCameraInfo(uint width, uint height, double fovRadians)
Parameters
Type | Name | Description |
---|---|---|
System.UInt32 | width | |
System.UInt32 | height | |
System.Double | fovRadians |
BuildCameraInfo(UInt32, UInt32, Double, Double, Double)
Builds up the camera info given width, height, focal length and sensor size
Declaration
public void BuildCameraInfo(uint width, uint height, double focalLengthMM, double sensorSizeXMM, double sensorSizeYMM)
Parameters
Type | Name | Description |
---|---|---|
System.UInt32 | width | Width of camera in pixels. |
System.UInt32 | height | Height of camera in pixels. |
System.Double | focalLengthMM | Focal length in millimeters. |
System.Double | sensorSizeXMM | Sensor width in millimeters. |
System.Double | sensorSizeYMM | Sensor height in millimeters. |
Update()
Declaration
public void Update()