sensor_msgs

Summary

sensor_msgs
Version:

1.12.3

Description:

This package defines messages for commonly used sensors, including cameras and scanning laser rangefinders.

Maintainers:
  • Tully Foote <tfoote AT osrfoundation DOT org>
Licenses:
  • BSD
Urls:
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:
Exports:
  • <architecture_independent/>

Types

Message types

sensor_msgs/JoyFeedbackArray
Field:

This message publishes values for multiple feedback at once.

# This message publishes values for multiple feedback at once. 
JoyFeedback[] array
sensor_msgs/Joy
Field:

Reports the state of a joysticks axes and buttons.

# Reports the state of a joysticks axes and buttons.
Header header           # timestamp in the header is the time the data is received from the joystick
float32[] axes          # the axes measurements from a joystick
int32[] buttons         # the buttons measurements from a joystick 
sensor_msgs/LaserScan
Field:
  • header (std_msgs/Header) –
  • angle_min (float32) –
  • angle_max (float32) –
  • angle_increment (float32) –
  • time_increment (float32) –
  • scan_time (float32) –
  • range_min (float32) –
  • range_max (float32) –
  • ranges[] (float32) –
  • intensities[] (float32) –

Single scan from a planar laser range-finder

If you have another ranging device with different behavior (e.g. a sonar array), please find or create a different message, since applications will make fairly laser-specific assumptions about this data

# Single scan from a planar laser range-finder
#
# If you have another ranging device with different behavior (e.g. a sonar
# array), please find or create a different message, since applications
# will make fairly laser-specific assumptions about this data

Header header            # timestamp in the header is the acquisition time of 
                         # the first ray in the scan.
                         #
                         # in frame frame_id, angles are measured around 
                         # the positive Z axis (counterclockwise, if Z is up)
                         # with zero angle being forward along the x axis
                         
float32 angle_min        # start angle of the scan [rad]
float32 angle_max        # end angle of the scan [rad]
float32 angle_increment  # angular distance between measurements [rad]

float32 time_increment   # time between measurements [seconds] - if your scanner
                         # is moving, this will be used in interpolating position
                         # of 3d points
float32 scan_time        # time between scans [seconds]

float32 range_min        # minimum range value [m]
float32 range_max        # maximum range value [m]

float32[] ranges         # range data [m] (Note: values < range_min or > range_max should be discarded)
float32[] intensities    # intensity data [device-specific units].  If your
                         # device does not provide intensities, please leave
                         # the array empty.
sensor_msgs/PointField
Constant:
  • INT8 (uint8):1
  • UINT8 (uint8):2
  • INT16 (uint8):3
  • UINT16 (uint8):4
  • INT32 (uint8):5
  • UINT32 (uint8):6
  • FLOAT32 (uint8):7
  • FLOAT64 (uint8):8
Field:
  • name (string) –
  • offset (uint32) –
  • datatype (uint8) –
  • count (uint32) –

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

# This message holds the description of one point entry in the
# PointCloud2 message format.
uint8 INT8    = 1
uint8 UINT8   = 2
uint8 INT16   = 3
uint8 UINT16  = 4
uint8 INT32   = 5
uint8 UINT32  = 6
uint8 FLOAT32 = 7
uint8 FLOAT64 = 8

string name      # Name of field
uint32 offset    # Offset from start of point struct
uint8  datatype  # Datatype enumeration, see above
uint32 count     # How many elements in the field
sensor_msgs/CameraInfo
Field:
  • header (std_msgs/Header) –
  • height (uint32) –
  • width (uint32) –
  • distortion_model (string) –
  • D[] (float64) –
  • K[9] (float64) –
  • R[9] (float64) –
  • P[12] (float64) –
  • binning_x (uint32) –
  • binning_y (uint32) –
  • roi
Image acquisition info #
Time of image acquisition, camera coordinate frame ID
# 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.

#######################################################################
#                     Image acquisition info                          #
#######################################################################

# Time of image acquisition, camera coordinate frame ID
Header 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 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


#######################################################################
#                      Calibration Parameters                         #
#######################################################################
# These are fixed during camera calibration. Their values will be the #
# same in all messages until the camera is recalibrated. Note that    #
# self-calibrating systems may "recalibrate" frequently.              #
#                                                                     #
# The internal parameters can be used to warp a raw (distorted) image #
# to:                                                                 #
#   1. An undistorted image (requires D and K)                        #
#   2. A rectified image (requires D, K, R)                           #
# The projection matrix P projects 3D points into the rectified image.#
#######################################################################

# The image dimensions with which the camera was calibrated. Normally
# this will be the full camera resolution in pixels.
uint32 height
uint32 width

# 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 sufficent.
string distortion_model

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

# 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).
float64[9]  K # 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.
float64[9]  R # 3x3 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.
float64[12] P # 3x4 row-major matrix


#######################################################################
#                      Operational Parameters                         #
#######################################################################
# These define the image region actually captured by the camera       #
# driver. Although they affect the geometry of the output image, they #
# may be changed freely without recalibrating the camera.             #
#######################################################################

# 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).
uint32 binning_x
uint32 binning_y

# 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).
RegionOfInterest roi
sensor_msgs/PointCloud
Field:

This message holds a collection of 3d points, plus optional additional information about each point.

Time of sensor data acquisition, coordinate frame ID.

# This message holds a collection of 3d points, plus optional additional
# information about each point.

# Time of sensor data acquisition, coordinate frame ID.
Header header

# Array of 3d points. Each Point32 should be interpreted as a 3d point
# in the frame given in the header.
geometry_msgs/Point32[] points

# Each channel should have the same number of elements as points array,
# and the data in each channel should correspond 1:1 with each point.
# Channel names in common practice are listed in ChannelFloat32.msg.
ChannelFloat32[] channels
sensor_msgs/MultiEchoLaserScan
Field:
  • header (std_msgs/Header) –
  • angle_min (float32) –
  • angle_max (float32) –
  • angle_increment (float32) –
  • time_increment (float32) –
  • scan_time (float32) –
  • range_min (float32) –
  • range_max (float32) –
  • ranges[] (sensor_msgs/LaserEcho) –
  • intensities[] (sensor_msgs/LaserEcho) –

Single scan from a multi-echo planar laser range-finder

If you have another ranging device with different behavior (e.g. a sonar array), please find or create a different message, since applications will make fairly laser-specific assumptions about this data

# Single scan from a multi-echo planar laser range-finder
#
# If you have another ranging device with different behavior (e.g. a sonar
# array), please find or create a different message, since applications
# will make fairly laser-specific assumptions about this data

Header header            # timestamp in the header is the acquisition time of 
                         # the first ray in the scan.
                         #
                         # in frame frame_id, angles are measured around 
                         # the positive Z axis (counterclockwise, if Z is up)
                         # with zero angle being forward along the x axis
                         
float32 angle_min        # start angle of the scan [rad]
float32 angle_max        # end angle of the scan [rad]
float32 angle_increment  # angular distance between measurements [rad]

float32 time_increment   # time between measurements [seconds] - if your scanner
                         # is moving, this will be used in interpolating position
                         # of 3d points
float32 scan_time        # time between scans [seconds]

float32 range_min        # minimum range value [m]
float32 range_max        # maximum range value [m]

LaserEcho[] ranges       # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)
                         # +Inf measurements are out of range
                         # -Inf measurements are too close to determine exact distance.
LaserEcho[] intensities  # intensity data [device-specific units].  If your
                         # device does not provide intensities, please leave
                         # the array empty.
sensor_msgs/JointState
Field:
  • header (std_msgs/Header) –
  • name[] (string) –
  • position[] (float64) –
  • velocity[] (float64) –
  • effort[] (float64) –

This is a message that holds data to describe the state of a set of torque controlled joints.

The state of each joint (revolute or prismatic) is defined by:
  • the position of the joint (rad or m),
  • the velocity of the joint (rad/s or m/s) and
  • the effort that is applied in the joint (Nm or N).

Each joint is uniquely identified by its name The header specifies the time at which the joint states were recorded. All the joint states in one message have to be recorded at the same time.

This message consists of a multiple arrays, one for each part of the joint state. The goal is to make each of the fields optional. When e.g. your joints have no effort associated with them, you can leave the effort array empty.

All arrays in this message should have the same size, or be empty. This is the only way to uniquely associate the joint name with the correct states.

# This is a message that holds data to describe the state of a set of torque controlled joints. 
#
# The state of each joint (revolute or prismatic) is defined by:
#  * the position of the joint (rad or m),
#  * the velocity of the joint (rad/s or m/s) and 
#  * the effort that is applied in the joint (Nm or N).
#
# Each joint is uniquely identified by its name
# The header specifies the time at which the joint states were recorded. All the joint states
# in one message have to be recorded at the same time.
#
# This message consists of a multiple arrays, one for each part of the joint state. 
# The goal is to make each of the fields optional. When e.g. your joints have no
# effort associated with them, you can leave the effort array empty. 
#
# All arrays in this message should have the same size, or be empty.
# This is the only way to uniquely associate the joint name with the correct
# states.


Header header

string[] name
float64[] position
float64[] velocity
float64[] effort
sensor_msgs/Imu
Field:

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.

# 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.

Header header

geometry_msgs/Quaternion orientation
float64[9] orientation_covariance # Row major about x, y, z axes

geometry_msgs/Vector3 angular_velocity
float64[9] angular_velocity_covariance # Row major about x, y, z axes

geometry_msgs/Vector3 linear_acceleration
float64[9] linear_acceleration_covariance # Row major x, y z 
sensor_msgs/Range
Field:
  • header (std_msgs/Header) –
  • radiation_type (uint8) –
  • field_of_view (float32) –
  • min_range (float32) –
  • max_range (float32) –
  • range (float32) –
Constant:
  • ULTRASOUND (uint8):0
  • INFRARED (uint8):1

Single range reading from an active ranger that emits energy and reports one range reading that is valid along an arc at the distance measured. This message is not appropriate for laser scanners. See the LaserScan message if you are working with a laser scanner.

This message also can represent a fixed-distance (binary) ranger. This sensor will have min_range===max_range===distance of detection. These sensors follow REP 117 and will output -Inf if the object is detected and +Inf if the object is outside of the detection range.

# Single range reading from an active ranger that emits energy and reports
# one range reading that is valid along an arc at the distance measured. 
# This message is  not appropriate for laser scanners. See the LaserScan
# message if you are working with a laser scanner.

# This message also can represent a fixed-distance (binary) ranger.  This
# sensor will have min_range===max_range===distance of detection.
# These sensors follow REP 117 and will output -Inf if the object is detected
# and +Inf if the object is outside of the detection range.

Header header           # timestamp in the header is the time the ranger
                        # returned the distance reading

# Radiation type enums
# If you want a value added to this list, send an email to the ros-users list
uint8 ULTRASOUND=0
uint8 INFRARED=1

uint8 radiation_type    # the type of radiation used by the sensor
                        # (sound, IR, etc) [enum]

float32 field_of_view   # the size of the arc that the distance reading is
                        # valid for [rad]
                        # the object causing the range reading may have
                        # been anywhere within -field_of_view/2 and
                        # field_of_view/2 at the measured range. 
                        # 0 angle corresponds to the x-axis of the sensor.

float32 min_range       # minimum range value [m]
float32 max_range       # maximum range value [m]
                        # Fixed distance rangers require min_range==max_range

float32 range           # range data [m]
                        # (Note: values < range_min or > range_max
                        # should be discarded)
                        # Fixed distance rangers only output -Inf or +Inf.
                        # -Inf represents a detection within fixed distance.
                        # (Detection too close to the sensor to quantify)
                        # +Inf represents no detection within the fixed distance.
                        # (Object out of range)
sensor_msgs/CompressedImage
Field:

This message contains a compressed image

# This message contains a compressed image

Header 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

string format        # Specifies the format of the data
                     #   Acceptable values:
                     #     jpeg, png
uint8[] data         # Compressed image buffer
sensor_msgs/NavSatStatus
Constant:
  • STATUS_NO_FIX (int8):-1
  • STATUS_FIX (int8):0
  • STATUS_SBAS_FIX (int8):1
  • STATUS_GBAS_FIX (int8):2
  • SERVICE_GPS (uint16):1
  • SERVICE_GLONASS (uint16):2
  • SERVICE_COMPASS (uint16):4
  • SERVICE_GALILEO (uint16):8
Field:
  • status (int8) –
  • service (uint16) –

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.

# 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.

int8 STATUS_NO_FIX =  -1        # unable to fix position
int8 STATUS_FIX =      0        # unaugmented fix
int8 STATUS_SBAS_FIX = 1        # with satellite-based augmentation
int8 STATUS_GBAS_FIX = 2        # with ground-based augmentation

int8 status

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

uint16 SERVICE_GPS =     1
uint16 SERVICE_GLONASS = 2
uint16 SERVICE_COMPASS = 4      # includes BeiDou.
uint16 SERVICE_GALILEO = 8

uint16 service
sensor_msgs/RelativeHumidity
Field:
  • header (std_msgs/Header) –
  • relative_humidity (float64) –
  • variance (float64) –

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

# 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 header             # timestamp of the measurement
                          # frame_id is the location of the humidity sensor

float64 relative_humidity # 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

float64 variance          # 0 is interpreted as variance unknown
sensor_msgs/JoyFeedback
Constant:
  • TYPE_LED (uint8):0
  • TYPE_RUMBLE (uint8):1
  • TYPE_BUZZER (uint8):2
Field:
  • type (uint8) –
  • id (uint8) –
  • intensity (float32) –

Declare of the type of feedback

# Declare of the type of feedback
uint8 TYPE_LED    = 0
uint8 TYPE_RUMBLE = 1
uint8 TYPE_BUZZER = 2

uint8 type

# This will hold an id number for each type of each feedback.
# Example, the first led would be id=0, the second would be id=1
uint8 id

# Intensity of the feedback, from 0.0 to 1.0, inclusive.  If device is
# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.
float32 intensity
sensor_msgs/NavSatFix
Field:
  • header (std_msgs/Header) –
  • status (sensor_msgs/NavSatStatus) –
  • latitude (float64) –
  • longitude (float64) –
  • altitude (float64) –
  • position_covariance[9] (float64) –
  • position_covariance_type (uint8) –
Constant:
  • COVARIANCE_TYPE_UNKNOWN (uint8):0
  • COVARIANCE_TYPE_APPROXIMATED (uint8):1
  • COVARIANCE_TYPE_DIAGONAL_KNOWN (uint8):2
  • COVARIANCE_TYPE_KNOWN (uint8):3

Navigation Satellite fix for any Global Navigation Satellite System

Specified using the WGS 84 reference ellipsoid

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.
# Navigation Satellite fix for any Global Navigation Satellite System
#
# Specified using the WGS 84 reference ellipsoid

# 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.
Header header

# satellite fix status information
NavSatStatus status

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

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

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

# 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.

float64[9] position_covariance

# 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.

uint8 COVARIANCE_TYPE_UNKNOWN = 0
uint8 COVARIANCE_TYPE_APPROXIMATED = 1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2
uint8 COVARIANCE_TYPE_KNOWN = 3

uint8 position_covariance_type
sensor_msgs/Image
Field:
  • header (std_msgs/Header) –
  • height (uint32) –
  • width (uint32) –
  • encoding (string) –
  • is_bigendian (uint8) –
  • step (uint32) –
  • data[] (uint8) –

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

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

Header 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

uint32 height         # image height, that is, number of rows
uint32 width          # image width, that is, number of columns

# 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.sourceforge.net and send an email proposing a new encoding.

string encoding       # Encoding of pixels -- channel meaning, ordering, size
                      # taken from the list of strings in include/sensor_msgs/image_encodings.h

uint8 is_bigendian    # is this data bigendian?
uint32 step           # Full row length in bytes
uint8[] data          # actual matrix data, size is (step * rows)
sensor_msgs/FluidPressure
Field:
  • header (std_msgs/Header) –
  • fluid_pressure (float64) –
  • variance (float64) –

Single pressure reading. This message is appropriate for measuring the pressure inside of a fluid (air, water, etc). This also includes atmospheric or barometric pressure.

This message is not appropriate for force/pressure contact sensors.

# Single pressure reading.  This message is appropriate for measuring the
# pressure inside of a fluid (air, water, etc).  This also includes
# atmospheric or barometric pressure.

# This message is not appropriate for force/pressure contact sensors.

Header header           # timestamp of the measurement
                        # frame_id is the location of the pressure sensor

float64 fluid_pressure  # Absolute pressure reading in Pascals.

float64 variance        # 0 is interpreted as variance unknown
sensor_msgs/TimeReference
Field:

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

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

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

time   time_ref  # corresponding time from this external source
string source    # (optional) name of time source
sensor_msgs/RegionOfInterest
Field:
  • x_offset (uint32) –
  • y_offset (uint32) –
  • height (uint32) –
  • width (uint32) –
  • do_rectify (bool) –

This message is used to specify a region of interest within an image.

When used to specify the ROI setting of the camera when the image was taken, the height and width fields should either match the height and width fields for the associated image; or height = width = 0 indicates that the full resolution image was captured.

# This message is used to specify a region of interest within an image.
#
# When used to specify the ROI setting of the camera when the image was
# taken, the height and width fields should either match the height and
# width fields for the associated image; or height = width = 0
# indicates that the full resolution image was captured.

uint32 x_offset  # Leftmost pixel of the ROI
                 # (0 if the ROI includes the left edge of the image)
uint32 y_offset  # Topmost pixel of the ROI
                 # (0 if the ROI includes the top edge of the image)
uint32 height    # Height of ROI
uint32 width     # Width of ROI

# True if a distinct rectified ROI should be calculated from the "raw"
# ROI in this message. Typically this should be False if the full image
# is captured (ROI not used), and True if a subwindow is captured (ROI
# used).
bool do_rectify
sensor_msgs/LaserEcho
Field:
  • echoes[] (float32) –

This message is a submessage of MultiEchoLaserScan and is not intended to be used separately.

# This message is a submessage of MultiEchoLaserScan and is not intended
# to be used separately.

float32[] echoes  # Multiple values of ranges or intensities.
                  # Each array represents data from the same angle increment.
sensor_msgs/MagneticField
Field:
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
# Measurement of the Magnetic Field vector at a specific location.

# 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


Header header                        # timestamp is the time the
                                     # field was measured
                                     # frame_id is the location and orientation
                                     # of the field measurement

geometry_msgs/Vector3 magnetic_field # x, y, and z components of the
                                     # field vector in Tesla
                                     # If your sensor does not output 3 axes,
                                     # put NaNs in the components not reported.

float64[9] magnetic_field_covariance # Row major about x, y, z axes
                                     # 0 is interpreted as variance unknown
sensor_msgs/PointCloud2
Field:
  • header (std_msgs/Header) –
  • height (uint32) –
  • width (uint32) –
  • fields[] (sensor_msgs/PointField) –
  • is_bigendian (bool) –
  • point_step (uint32) –
  • row_step (uint32) –
  • data[] (uint8) –
  • is_dense (bool) –

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.

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

# 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.

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

# 2D structure of the point cloud. If the cloud is unordered, height is
# 1 and width is the length of the point cloud.
uint32 height
uint32 width

# Describes the channels and their layout in the binary data blob.
PointField[] fields

bool    is_bigendian # Is this data bigendian?
uint32  point_step   # Length of a point in bytes
uint32  row_step     # Length of a row in bytes
uint8[] data         # Actual point data, size is (row_step*height)

bool is_dense        # True if there are no invalid points
sensor_msgs/Temperature
Field:
  • header (std_msgs/Header) –
  • temperature (float64) –
  • variance (float64) –

Single temperature reading.

# Single temperature reading.

Header header           # timestamp is the time the temperature was measured
                        # frame_id is the location of the temperature reading

float64 temperature     # Measurement of the Temperature in Degrees Celsius

float64 variance        # 0 is interpreted as variance unknown
sensor_msgs/ChannelFloat32
Field:
  • name (string) –
  • values[] (float32) –

This message is used by the PointCloud message to hold optional data associated with each point in the cloud. The length of the values array should be the same as the length of the points array in the PointCloud, and each value should be associated with the corresponding point.

Channel names in existing practice include:
“u”, “v” - row and column (respectively) in the left stereo image.
This is opposite to usual conventions but remains for historical reasons. The newer PointCloud2 message has no such problem.
“rgb” - For point clouds produced by color stereo cameras. uint8
(R,G,B) values packed into the least significant 24 bits, in order.

“intensity” - laser or pixel intensity. “distance”

The channel name should give semantics of the channel (e.g. “intensity” instead of “value”).

# This message is used by the PointCloud message to hold optional data
# associated with each point in the cloud. The length of the values
# array should be the same as the length of the points array in the
# PointCloud, and each value should be associated with the corresponding
# point.

# Channel names in existing practice include:
#   "u", "v" - row and column (respectively) in the left stereo image.
#              This is opposite to usual conventions but remains for
#              historical reasons. The newer PointCloud2 message has no
#              such problem.
#   "rgb" - For point clouds produced by color stereo cameras. uint8
#           (R,G,B) values packed into the least significant 24 bits,
#           in order.
#   "intensity" - laser or pixel intensity.
#   "distance"

# The channel name should give semantics of the channel (e.g.
# "intensity" instead of "value").
string name

# The values array should be 1-1 with the elements of the associated
# PointCloud.
float32[] values
sensor_msgs/MultiDOFJointState
Field:

Representation of state for joints with multiple degrees of freedom, following the structure of JointState.

It is assumed that a joint in a system corresponds to a transform that gets applied along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) and those 3DOF can be expressed as a transformation matrix, and that transformation matrix can be converted back to (x, y, yaw)

Each joint is uniquely identified by its name The header specifies the time at which the joint states were recorded. All the joint states in one message have to be recorded at the same time.

This message consists of a multiple arrays, one for each part of the joint state. The goal is to make each of the fields optional. When e.g. your joints have no wrench associated with them, you can leave the wrench array empty.

All arrays in this message should have the same size, or be empty. This is the only way to uniquely associate the joint name with the correct states.

# Representation of state for joints with multiple degrees of freedom, 
# following the structure of JointState.
#
# It is assumed that a joint in a system corresponds to a transform that gets applied 
# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)
# and those 3DOF can be expressed as a transformation matrix, and that transformation
# matrix can be converted back to (x, y, yaw)
#
# Each joint is uniquely identified by its name
# The header specifies the time at which the joint states were recorded. All the joint states
# in one message have to be recorded at the same time.
#
# This message consists of a multiple arrays, one for each part of the joint state. 
# The goal is to make each of the fields optional. When e.g. your joints have no
# wrench associated with them, you can leave the wrench array empty. 
#
# All arrays in this message should have the same size, or be empty.
# This is the only way to uniquely associate the joint name with the correct
# states.

Header header

string[] joint_names
geometry_msgs/Transform[] transforms
geometry_msgs/Twist[] twist
geometry_msgs/Wrench[] wrench
sensor_msgs/Illuminance
Field:
  • header (std_msgs/Header) –
  • illuminance (float64) –
  • variance (float64) –

Single photometric illuminance measurement. Light should be assumed to be measured along the sensor’s x-axis (the area of detection is the y-z plane). The illuminance should have a 0 or positive value and be received with the sensor’s +X axis pointing toward the light source.

Photometric illuminance is the measure of the human eye’s sensitivity of the intensity of light encountering or passing through a surface.

All other Photometric and Radiometric measurements should not use this message. This message cannot represent: Luminous intensity (candela/light source output) Luminance (nits/light output per area) Irradiance (watt/area), etc.

# Single photometric illuminance measurement.  Light should be assumed to be
# measured along the sensor's x-axis (the area of detection is the y-z plane).
# The illuminance should have a 0 or positive value and be received with
# the sensor's +X axis pointing toward the light source.

# Photometric illuminance is the measure of the human eye's sensitivity of the
# intensity of light encountering or passing through a surface.

# All other Photometric and Radiometric measurements should
# not use this message.
# This message cannot represent:
# Luminous intensity (candela/light source output)
# Luminance (nits/light output per area)
# Irradiance (watt/area), etc.

Header header           # timestamp is the time the illuminance was measured
                        # frame_id is the location and direction of the reading

float64 illuminance     # Measurement of the Photometric Illuminance in Lux.

float64 variance        # 0 is interpreted as variance unknown

Service types

sensor_msgs/SetCameraInfo
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –

This service requests that a camera stores the given CameraInfo as that camera’s calibration information.

The width and height in the camera_info field should match what the camera is currently outputting on its camera_info topic, and the camera will assume that the region of the imager that is being referred to is the region that the camera is currently capturing.

# This service requests that a camera stores the given CameraInfo 
# as that camera's calibration information.
#
# The width and height in the camera_info field should match what the
# camera is currently outputting on its camera_info topic, and the camera
# will assume that the region of the imager that is being referred to is
# the region that the camera is currently capturing.

sensor_msgs/CameraInfo camera_info # The camera_info to store
---
bool success          # True if the call succeeded
string status_message # Used to give details about success