Skip to content

ROS2 Sensor Messages

CameraInfo

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.

d class-attribute instance-attribute

d: sequence[float64] = default_field([])

The distortion parameters, size depending on the distortion model. For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).

distortion_model class-attribute instance-attribute

distortion_model: str = ''

The distortion model used. Supported models are listed in sensor_msgs/distortion_models.hpp. For most cameras, "plumb_bob" - a simple model of radial and tangential distortion - is sufficent.

header class-attribute instance-attribute

header: Header = default_field(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

k class-attribute instance-attribute

k: array[float64, 9] = default_field([0] * 9)

3x3 row-major matrix 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).

p class-attribute instance-attribute

p: array[float64, 12] = default_field([0] * 12)

3x4 row-major matrix 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.

r class-attribute instance-attribute

r: array[float64, 9] = default_field([0] * 9)

3x3 row-major matrix 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.

roi class-attribute instance-attribute

roi: RegionOfInterest = default_field(RegionOfInterest)

Region of interest (subwindow of full camera resolution), given in full resolution (unbinned) image coordinates. A particular ROI always denotes the same window of pixels on the camera sensor, regardless of binning settings. The default setting of roi (all values 0) is considered the same as full resolution (roi.width = width, roi.height = height).

CompressedImage

This message contains a compressed image.

data class-attribute instance-attribute

data: sequence[uint8] = default_field([])

Compressed image buffer

format class-attribute instance-attribute

format: str = ''

Specifies the format of the data Acceptable values: jpeg, png, tiff

header class-attribute instance-attribute

header: Header = default_field(Header)

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 cameara +x should point to the right in the image +y should point down in the image +z should point into to plane of the image

Image

This message contains an uncompressed image (0, 0) is at top-left corner of image

data class-attribute instance-attribute

data: sequence[uint8] = default_field([])

actual matrix data, size is (step * rows)

encoding class-attribute instance-attribute

encoding: str = ''

The legal values for encoding are in file src/image_encodings.cpp If you want to standardize a new string format, join ros-users@lists.ros.org and send an email proposing a new encoding. Encoding of pixels -- channel meaning, ordering, size taken from the list of strings in include/sensor_msgs/image_encodings.hpp

header class-attribute instance-attribute

header: Header = default_field(Header)

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 cameara +x should point to the right in the image +y should point down in the image +z should point into to plane of the image If the frame_id here and the frame_id of the CameraInfo message associated with the image conflict the behavior is undefined

height class-attribute instance-attribute

height: uint32 = 0

image height, that is, number of rows

is_bigendian class-attribute instance-attribute

is_bigendian: uint8 = 0

is this data bigendian?

step class-attribute instance-attribute

step: uint32 = 0

Full row length in bytes

width class-attribute instance-attribute

width: uint32 = 0

image width, that is, number of columns

Imu

This is a message to hold data from an IMU (Inertial Measurement Unit)

Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec

If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the datasheet, just put those along the diagonal) A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the data a covariance will have to be assumed or gotten from some other source

If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation estimate), please set element 0 of the associated covariance matrix to -1 If you are interpreting this message, please check for a value of -1 in the first element of each covariance matrix, and disregard the associated estimate.

angular_velocity_covariance class-attribute instance-attribute

angular_velocity_covariance: array[float64, 9] = (
    default_field([0] * 9)
)

Row major about x, y, z axes

linear_acceleration_covariance class-attribute instance-attribute

linear_acceleration_covariance: array[float64, 9] = (
    default_field([0] * 9)
)

Row major x, y z

orientation_covariance class-attribute instance-attribute

orientation_covariance: array[float64, 9] = default_field(
    [0] * 9
)

Row major about x, y, z axes

Navigation Satellite fix status for any Global Navigation Satellite System.

Whether to output an augmented fix is determined by both the fix type and the last time differential corrections were received. A fix is valid when status >= STATUS_FIX.

status class-attribute instance-attribute

status: int8 = 0

Bits defining which Global Navigation Satellite System signals were used by the receiver.

Navigation Satellite fix for any Global Navigation Satellite System

Specified using the WGS 84 reference ellipsoid

altitude class-attribute instance-attribute

altitude: float64 = 0

Altitude [m]. Positive is above the WGS 84 ellipsoid (quiet NaN if no altitude is available).

header class-attribute instance-attribute

header: Header = default_field(Header)

header.stamp specifies the ROS time for this measurement (the corresponding satellite time may be reported using the sensor_msgs/TimeReference message).

header.frame_id is the frame of reference reported by the satellite receiver, usually the location of the antenna. This is a Euclidean frame relative to the vehicle, not a reference ellipsoid.

latitude class-attribute instance-attribute

latitude: float64 = 0

Latitude [degrees]. Positive is north of equator; negative is south.

longitude class-attribute instance-attribute

longitude: float64 = 0

Longitude [degrees]. Positive is east of prime meridian; negative is west.

position_covariance class-attribute instance-attribute

position_covariance: array[float64, 9] = default_field(
    [0] * 9
)

Position covariance [m^2] defined relative to a tangential plane through the reported position. The components are East, North, and Up (ENU), in row-major order.

Beware: this coordinate system exhibits singularities at the poles.

position_covariance_type class-attribute instance-attribute

position_covariance_type: uint8 = 0

If the covariance of the fix is known, fill it in completely. If the GPS receiver provides the variance of each measurement, put them along the diagonal. If only Dilution of Precision is available, estimate an approximate covariance from that.

status class-attribute instance-attribute

status: NavSatStatus = default_field(NavSatStatus)

Satellite fix status information.

PointField

This message holds the description of one point entry in the PointCloud2 message format.

count class-attribute instance-attribute

count: uint32 = 0

How many elements in the field

datatype class-attribute instance-attribute

datatype: uint8 = 0

Datatype enumeration, see above

name class-attribute instance-attribute

name: str = ''

Name of field Common PointField names are x, y, z, intensity, rgb, rgba

offset class-attribute instance-attribute

offset: uint32 = 0

Offset from start of point struct

PointCloud2

This message holds a collection of N-dimensional points, which may contain additional information such as normals, intensity, etc. The point data is stored as a binary blob, its layout described by the contents of the "fields" array.

The point cloud data may be organized 2d (image-like) or 1d (unordered). Point clouds organized as 2d images may be produced by camera depth sensors such as stereo or time-of-flight.

data class-attribute instance-attribute

data: sequence[uint8] = default_field([])

Actual point data, size is (row_step*height)

fields class-attribute instance-attribute

fields: sequence[PointField] = default_field([])

Describes the channels and their layout in the binary data blob.

header class-attribute instance-attribute

header: Header = default_field(Header)

Time of sensor data acquisition, and the coordinate frame ID (for 3d points).

is_bigendian class-attribute instance-attribute

is_bigendian: bool = False

Is this data bigendian?

is_dense class-attribute instance-attribute

is_dense: bool = False

True if there are no invalid points

point_step class-attribute instance-attribute

point_step: uint32 = 0

Length of a point in bytes

row_step class-attribute instance-attribute

row_step: uint32 = 0

Length of a row in bytes

RelativeHumidity

Single reading from a relative humidity sensor. Defines the ratio of partial pressure of water vapor to the saturated vapor pressure at a temperature.

header class-attribute instance-attribute

header: Header = default_field(Header)

timestamp of the measurement frame_id is the location of the humidity sensor

relative_humidity class-attribute instance-attribute

relative_humidity: float64 = 0

Expression of the relative humidity from 0.0 to 1.0. 0.0 is no partial pressure of water vapor 1.0 represents partial pressure of saturation

variance class-attribute instance-attribute

variance: float64 = 0

0 is interpreted as variance unknown

Temperature

Single temperature reading.

header class-attribute instance-attribute

header: Header = default_field(Header)

timestamp is the time the temperature was measured frame_id is the location of the temperature reading

temperature class-attribute instance-attribute

temperature: float64 = 0

Measurement of the Temperature in Degrees Celsius.

variance class-attribute instance-attribute

variance: float64 = 0

0 is interpreted as variance unknown.

TimeReference

Measurement from an external time source not actively synchronized with the system clock.

header class-attribute instance-attribute

header: Header = default_field(Header)

stamp is system time for which measurement was valid frame_id is not used

source class-attribute instance-attribute

source: str = ''

(optional) name of time source

time_ref class-attribute instance-attribute

time_ref: Time = default_field(Time)

corresponding time from this external source