6. ROS API

The ROS API for the MultiSense SL sensor, provided by the ros_driver executable, is split into distinct subsystems for each piece of hardware. Each of these subsystems is documented below.

Streams from the sensor are initiated on an "on-demand" basis. That is, on subscription of a given data stream (such as /multisense/left/image_rect), the driver will initialize the data stream on the sensor. Thus, the driver uses very little bandwidth and CPU when there are no subscriptions to any of the ROS topics.

6.1. Camera Topics

Camera topics outlined below are supported on the MultiSense SL.

All */camera_info topics have scaled a P projection matrix, D distortion coefficients, scaled K distorted projection matrix, and R rectification matrix corresponding to their parent image topic.

The focal lengths and image center in K and P are scaled based on the current operating resolution. Both the plumb_bob and rational polynomial distortion models are supported.

6.1.1. Depth Camera

Topic

/multisense/camera_info

Notes

Camera projection matrix and metadata. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/depth

Notes

Depth image in canonical representation (values are depth in meters and are float32).
Depth images replace disparity images as the standard (See REP 118).

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/openni_depth

Notes

Depth image in OpenNI representation (values are depth in millimeters and are uint16).
Depth images replace disparity images as the standard (See REP 118).
Subtopics /compressed & /theora are for use with image_transport.
This topic version uses less bandwidth than the traditional depth image and is able to be compressed with image transport.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/image_points2

Notes

Greyscale stereo point cloud. Each point contains 4 fields (x, y, z, lumanince).
See the PCL Documentation for more information.

Message Type

sensor_msgs/PointCloud2

Minimum Firmware

2.0

Topic

/multisense/image_points2_color

Notes

Color stereo point cloud. Each point contains 4 fields (x, y, z, rgb).
See the PCL Documentation for more information.

Color images are rectified on the host machine before combining with range data.

Message Type

sensor_msgs/PointCloud2

Minimum Firmware

2.0

Topic

/multisense/organized_image_points2

Notes

Stereo point cloud. Each point contains 4 fields (x,y,z, lumanince).
See the pcl wiki page for more information.
The number of points is equal to the size of the left rectified camera image, allowing for direct indexing based off camera pixel coordinates. Invalid points are populated with std::numeric_limits::quiet_NaN values for the X,Y, and Z point fields.

Message Type

sensor_msgs/PointCloud2

Minimum Firmware

2.0

Topic

/multisense/organized_image_points2_color

Notes

Color stereo point cloud. Each point contains 4 fields (x,y,z, rgb).
See the pcl wiki page for more information.
Color images are rectified on the host machine before combining with range data.

The number of points is equal to the size of the left rectified camera image, allowing for direct indexing based off camera pixel coordinates. Invalid points are populated with std::numeric_limits::quiet_NaN values for the X,Y, and Z point fields.

Message Type

sensor_msgs/PointCloud2

Minimum Firmware

2.0

Topic

/multisense/left/disparity

Notes

Left disparity image in "mono16" format (units are 1/16th of a disparity.)

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/left/disparity_image

Notes

Left disparity image in DisparityImage format. Note that this type has been deprecated by ROS, see REP-118.

Message Type

stereo_msgs/DisparityImage

Minimum Firmware

2.0

Topic

/multisense/left/disparity/camera_info

Notes

Rectified camera projection matrix and metadata corresponding to the left disparity topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/right/disparity

Notes

Right disparity image in "mono8" format. This stream is provided for debugging purposes ONLY. Please use the left/disparity topic for ALL purposes. Note that this topic will only be published if the left/disparity topic is also subscribed to.

Message Type

sensor_msgs/Image

Minimum Firmware

3.0
In the 3.0_beta release these images were not passed through the left/right-discrepancy or post-stereo filters. Releases 3.0 and later do pass these images through the filters.

Topic

/multisense/right/disparity_image

Notes

Right disparity image in DisparityImage format. This stream is provided for debugging purposes ONLY. Please use the left/disparity topic for ALL purposes. Note that this type has been deprecated by ROS, see REP-118.

Message Type

stereo_msgs/DisparityImage

Minimum Firmware

2.0

Topic

/multisense/right/disparity/camera_info

Notes

Rectified camera projection matrix and metadata corresponding to the right disparity topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/left/cost

Notes

Left stereo cost in "mono8" format.
Higher values represent less confidence in the disparity value generated for that location.

Message Type

sensor_msgs/Image

Minimum Firmware

3.0
In the 3.0_beta release these images were not passed through the left/right-discrepancy or post-stereo filters. Releases 3.0 and later do pass these images through the filters.

Topic

/multisense/left/cost/camera_info

Notes

Rectified camera projection matrix and metadata corresponding to the cost image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

6.1.2. Left Camera

Topic

/multisense/left/camera_info

Notes

Camera projection matrix and metadata. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/left/image_rect

Notes

Rectified greyscale images from left camera in mono8 format.
Subtopics /compressed & /theora are for use with image_transport.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/left/image_rect/camera_info

Notes

Rectified camera projection matrix and metadata corresponding to the left rectified image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/left/image_rect_color

Notes

Rectified color images from left camera in RGB8 format.
Subtopics /compressed & /theora are for use with image_transport.
Color images are rectified on the host machine using OpenCV.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/left/image_rect_color/camera_info

Notes

Rectified camera projection matrix and metadata corresponding to the left rectified color image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/left/image_mono

Notes

Unrectified greyscale images from left camera in mono8 format.
Subtopics /compressed & /theora are for use with image_transport.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/left/image_mono/camera_info

Notes

Camera projection matrix and metadata corresponding to the left mono image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/left/image_color

Notes

Unrectified color images from left camera in RGB8 format.
Subtopics /compressed & /theora are for use with image_transport.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/left/image_color/camera_info

Notes

Camera projection matrix and metadata corresponding to the left color image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

6.1.3. Right Camera

Topic

/multisense/right/camera_info

Notes

Camera projection matrix and metadata. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/right/image_rect

Notes

Rectified greyscale images from right camera in mono8 format.
Subtopics /compressed & /theora are for use with image_transport.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/right/image_rect/camera_info

Notes

Rectified camera projection matrix and metadata corresponding to the right rectified mono image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

Topic

/multisense/right/image_mono

Notes

Unrectified greyscale images from right camera in mono8 format.
Subtopics /compressed & /theora are for use with image_transport.

Message Type

sensor_msgs/Image

Minimum Firmware

2.0

Topic

/multisense/right/image_mono/camera_info

Notes

Camera projection matrix and metadata corresponding to the right mono image topic. See the Camera Info Note at the top of this section for matrix scale information.

Message Type

sensor_msgs/CameraInfo

Minimum Firmware

2.0

In the current release, color images are not supported for the right camera.

6.1.4. Calibration

Topic

/multisense/calibration/device_info

Notes

Hardware and software versioning information.

Message Type

multisense_ros/DeviceInfo

Minimum Firmware

2.0

Topic

/multisense/calibration/raw_cam_cal

Notes

Rectification and stereo projection matrices:

  • unrectified camera matrix A (left_M, right_M)

  • distortion coefficients (left_D, right_D)

  • rectification transformation matrix (left_R, right_R)

  • new camera matrix A’ (left_P, right_P)

These matrices are for the maximum operating resolution of the MultiSense unit.

Message Type

multisense_ros/RawCamCal

Minimum Firmware

2.0

Topic

/multisense/calibration/raw_cam_config

Notes

Current operating resolution and camera parameters: fx, fy, cx, cy, tx, ty, tz, roll, pitch, and yaw.
These parameters have been scaled to the current operating resolution of the MultiSense unit.

Message Type

multisense_ros/RawCamCal

Minimum Firmware

2.0

Topic

/multisense/calibration/raw_cam_data

Notes

Synchronized left-rectified (greyscale) and left-disparity images.

Message Type

multisense_ros/RawCamData

Minimum Firmware

2.0

6.1.5. Histogram

Topic

/multisense/histogram

Notes

Image histograms for each of the 4 Bayer channels in the left camera image.
Each message contains the image size, fps, exposure time, and number of histogram bins.
The data field contains channels x bins elements, where each histogram is concatenated serially in the order green, red, blue, green.

Note that there must be a subscription to a MultiSense image topic for the histogram topic to be published.

Note that histograms from the MultiSense can only record 2^18 pixels in each intensity bin (this is limited by hardware buffers on the FPGA). Above that they saturate and the sum of all the histogram bins does not equal the number of pixels in the image.

Message Type

multisense_ros/Histogram

Minimum Firmware

3.1

6.2. Laser Topics

Laser topics are only supported for MultiSense SL units.

6.2.1. Laser Data

Topic

/multisense/lidar_points2

Notes

Laser point cloud. Each point contains 4 fields: x, y, z, and intensity.

Message Type

sensor_msgs/PointCloud2

Minimum Firmware

2.0

Topic

/multisense/lidar_points2_color

Notes

Laser point cloud. Each point contains 4 fields: x, y, z, and RGB color.

This topic published a point cloud for each laser scan where each laser point is colorized using its projected pixel value form the left camera image. If a 3D laser point does not project back into the camera it is not included in the point cloud for that colorized laser scan.

Message Type

sensor_msgs/PointCloud2

Minimum Firmware

2.0

Topic

/multisense/lidar_scan

Notes

Raw laser scan from device.

Message Type

sensor_msgs/LaserScan

Minimum Firmware

2.0

Topic

/multisense/joint_states

Notes

The joint state corresponding to the MultiSense SL spindle angle. Includes the joint position in radians as well as the current measured joint velocity in radians per second.

Message Type

sensor_msgs/JointState

Minimum Firmware

2.0

In Release 3.1 and 3.2, /multisense/joint_states is not present in the ROS driver.

6.2.2. Calibration

Topic /laser/calibration/raw_lidar_cal

Notes

The laser calibration, represented by the homogeneous transform matrices HCM (cameraToSpindleFixed) and HSL (laserToSpindle). See Overview for more information.

Message Type

multisense_ros/RawLidarCal

Minimum Firmware

2.0

Topic /laser/calibration/raw_lidar_data

Notes

Contains the raw laser scan data. This includes ranges, intensities, and the timestamps and spindle-angles for the start and end of each scan.

Message Type

multisense_ros/RawLidarData

Minimum Firmware

2.0

6.3. PPS Topics

PPS topics are supported for all MultiSense products including: SL, S7, S7S, and S21.

Topic

/multisense/pps

Notes

Contains the time of the last PPS in the sensor’s clock frame. Published once per second, immediately after the pulse.

Message Type

std_msgs/Time

Minimum Firmware

2.2

Topic

/multisense/stamped_pps

Notes

Contains the time of the last PPS in the sensor’s clock frame. Published once per second, immediately after the pulse. Also includes the host time corresponding to this PPS event.

Message Type

multisense_ros/StampedPps

Minimum Firmware

2.2

Firmware version 2.1 contained a bug that could duplicate PPS events.

Firmware version 3.2 adds a directed streams implementation, allowing data streams to be sent to IP addresses that differ from control device. This changes the PPS implementation slightly and requires that a data stream (of any type) be created for PPS events to be emitted by the MultiSense {SL}. Prior to firmware 3.2, PPS events were emitted upon system boot.

6.4. IMU Topics

IMU topics are supported for MultiSense SL.

The ROS driver includes a command line tool for Querying and Changing the IMU Configuration.

Accelerometer and gyroscope messages may arrive out of order with each other.

The accelerometer and gyroscope are on two different chips with two different hardware clocks. The MultiSense attempts to estimate the skew between these clocks and the main clock, but this estimation may not be perfectly correct. Additionally, each chip has a hardware FIFO where sensor measurements are buffered before being dumped to an internal FIFO on the MultiSense. This can cause older gyro measurements to occur after newer accelerometer measurements.

To minimize latency these measurements are sent directly to the client without any sorting based on time. The best way to minimize these errors is to run the accelerometer and gyroscope at approximately the same frequency.

Note that clock skew is taken into account in the sensor head. You can treat all the measurements as though they were in the same timebase.

Topic

/multisense/imu/accelerometer

Notes

Raw accelerometer data. Each message contains 4 fields: time and x,y,z accelerations in g.

Message Type

multisense_ros/RawImuData

Minimum Firmware

2.3

Topic

/multisense/imu/accelerometer_vector

Notes

Accelerometer vector.

Message Type

geometry_msgs/Vector3Stamped

Minimum Firmware

2.3

Topic

/multisense/imu/gyroscope

Notes

Raw gyroscope data. Each message contains 4 fields: time and x,y,z rates in degrees-per-second.

Message Type

multisense_ros/RawImuData

Minimum Firmware

2.3

Topic

/multisense/imu/gyroscope_vector

Notes

Gyroscope vector.

Message Type

geometry_msgs/Vector3Stamped

Minimum Firmware

2.3

Topic

/multisense/imu/magnetometer

Notes

Raw magnetometer data. Each message contains 4 fields: time and x,y,z measurements in gauss.

Message Type

multisense_ros/RawImuData

Minimum Firmware

2.3

Topic

/multisense/imu/magnetometer_vector

Notes

Magnetometer vector.

Message Type

geometry_msgs/Vector3Stamped

Minimum Firmware

2.3

Topic

/multisense/imu/imu_data

Notes

Standard ROS IMU message. Note that the orientation quaternion is not set in the current implementation, only linear_acceleration and angular_velocity fields are populated.

Message Type

sensor_msgs::Imu

Minimum Firmware

2.3

6.5. Status Message

The status topic is supported for all MultiSense products including: SL, S7, S7S, and S21. Note that the units without laser will always return "false" for laserOk and laserMotorOk.

Topic

/multisense/status

Notes

This is a custom message, please see the table below for details.

Message Type

multisense_ros/DeviceStatus

Minimum Firmware

3.4

This custom message contains the following fields:

Field

Type

Notes

time

time

uptime

time

systemOk

bool

laserOk

bool

Will turn false if the laser reports an error or becomes non-responsive.

laserMotorOk

bool

Will turn false if the spindle motor stalls.

camerasOk

bool

imuOk

bool

externalLedsOk

bool

processingPipelineOk

bool

powerSupplyTemp

float32

Returned value is in Celsius and is obtained by a thermistor near the device.

fpgaTemp

float32

Returned value is in Celsius and is obtained by a thermistor near the device.

leftImagerTemp

float32

Returned value is in Celsius and is obtained by a thermistor near the device.

rightImagerTemp

float32

Returned value is in Celsius and is obtained by a thermistor near the device.

inputVoltage

float32

This field is not supported on the S7S.

inputCurrent

float32

Returned value is in amps. This field is not supported on the S7S.

fpgaPower

float32

Returned value is in watts.

logicPower

float32

Returned value is in watts.

imagerPower

float32

Returned value is in watts.

6.6. Parameters

These parameters employ dynamic_reconfigure, and can be modified at runtime by executing the following commands:

Noetic, Melodic, Kinetic

rosurn rqt_reconfigure rqt_reconfigure

Selecting "/multisense" from the drop-down list will bring up the following configurable parameters.

Parameter Data Type Description

resolution

string

Resolution of the camera images streamed from the sensor, in the format of "width x height x number_of_disparities". In the 3.0_beta and newer releases, each resolution can be configured for 64, 128, or 256 disparities. Since the hardware stereo core has a finite throughput, lower disparities will have the effect of increasing frame-rate at the cost of near-field coverage. Note that changing this value will pause image streams while rectification lookup table is recomputed.

fps

double

Frames per second.

gain

double

Camera gain.

auto_exposure

bool

Enable or disable auto exposure.

auto_exposure_max_time

int

Maximum time (in microseconds) that the AE algorithm will allow for frame capture.

auto_exposure_decay

int

Adjust the auto exposure decay. Increasing this parameter makes the auto exposure algorithm respond more slowly to changes in lighting.

auto_exposure_thresh

double

Adjust the auto exposure threshold. This parameter changes the overall scene brightness target for the AE algorithm.

exposure_time

double

Time (in seconds) for camera exposure. Ignored if auto exposure is enabled.

auto_white_balance

bool

Enable or disable auto white balance.

auto_white_balance_decay

int

Adjust auto white balance decay. Increasing this parameter makes the auto white balance algorithm respond more slowly to changes.

auto_white_balance_thresh

double

Adjust the auto white balance threshold.

white_balance_red

double

Adjust the red white balance. Ignored if auto white balance enabled.

white_balance_blue

double

Adjust the blue white balance. Ignored if auto white balance enabled.

stereo_post_filtering

double

Adjust the strength of the hardware stereo post-filter. This parameter only exists in firmware 3.0 or later.

lighting

bool

Enable or disable LEDs.

flash

bool

Enable or disable flashing of LEDs.

duty_cycle

double

Change brightness of LEDs (0 = Off, 1 = Full Brightness).

motor_speed

double

Change laser spindle speed in radians/second.

network_time_sync

bool

Enable network-based time sync between the host computer and sensor. If disabled, all datum timestamps will be in the frame of the MultiSense’s internal clock, which is free-running from zero on power up. This parameter only exists in firmware 2.1 or later.

border_clip_type

int

Can either be 0:rectangular or 1:circular.

When rectangular it operates like the legacy MULITSENSE_POINTCLOUD_BORDER_CLIP environment variable, excluding a border_clip_value number of points from the edge of the output point cloud.

When circular it generates a circle, centered around the center of the image, whose radius is equal to the radius of the circle which circumscribes the image minus the border_clip_value.

Disparity pixels which lie within these regions are included in the point cloud and pixels which lie outside are excluded. This removes points on the edge of the image where the lens model is less accurate and results in poor stereo matches.

border_clip_value

double

Number of pixels trimmed from the edges of disparity images. See border_clip_type for more detailed usage information.

crop_mode

bool

When true, crops a 4MP imager to 2MP resolution, FOV, and frame rate limits. The crop_offset parameter can then adjust the position of this cropped view. Note that changing this value will pause image streams while rectification lookup table is recomputed.

crop_offset

int

Offset from the bottom of the imager’s FOV for the cropped FOV. A value of 480 will center the ROI in the 4MP imager. Note that changing this value will pause image streams while rectification lookup table is recomputed.

desired_transmit_delay

int

Desired transmit delay in milliseconds. If longer than interval between exposures, will be shortened so that the current frame is transmitted before the next frame capture.

max_pointcloud_range

double

The euclidean distance, in meters, for a point to be included in published pointclouds. Distances are computed from the focal point of the left_camera_optical frame.

  • The following IMU parameters will only be presented if the ROS driver detects that the MultiSense unit is running firmware v2.3 or greater.

  • Any IMU configuration changes will take effect after all IMU topic subscriptions have been closed.

Parameter Data Type Description

imu_samples_per_message

int

Adjust the number of IMU readings (aggregate from accel/gyro/mag sensors) that the device will accumulate before shipping over the network. This can be used to make tradeoffs between sample rates, processor load, and latency.

accelerometer_enabled

bool

Enable or disable the accelerometer sensor.

accelerometer_rate

int

Selects the sample rate index of the accelerometer.
Valid values are in [0, 6], corresponding to: 10, 25, 50, 100, 200, 400, and 1344 Hz.

accelerometer_range

int

Selects the sample range index of the accelerometer.
Valid values are in [0, 3], corresponding to: 2, 4, 8, and 16 g.

gyroscope_enabled

bool

Enable or disable the gyroscope sensor.

gyroscope_rate

int

Selects the sample rate index of the gyroscope.
Valid values are in [0, 3], corresponding to: 100, 200, 400, and 800 Hz.

gyroscope_range

int

Selects the sample range index of the gyroscope.
Valid values are in [0, 2], corresponding to 250, 500, and 2000 degrees-per-second.

magnetometer_enabled

bool

Enable or disable the magnetometer sensor.

magnetometer_rate

int

Selects the sample rate index of the magnetometer.
Valid values are in [0, 3], corresponding to 10, 25, 50, and 100 Hz.

magnetometer_range

int

Selects the sample range index of the magnetometer.
Valid values are in [0, 6], corresponding to: 1.3, 1.9, 2.5, 4.0, 4.7, 5.6, and 8.1 gauss.