ROS API

sr4k

The sr4k driver provides a ROS interface for Mesa Imaging SwissRanger devices (3000/4000) that use the libmesasr libraries.

Published Topics

camera/camera_info (sensor_msgs/CameraInfo)
  • Camera intrinsics for published images
distance/image_raw (sensor_msgs/Image)
  • 2D depth image
intensity/image_raw (sensor_msgs/Image)
  • 2D intensity image that corresponds to the depth image of distance/image_raw
pointcloud/cloud_raw (sensor_msgs/PointCloud)
  • 3D pointcloud generated from distance/image_raw

Services

camera/set_camera_info (sensor_msgs/SetCameraInfo)
  • Sets the camera's calibration

Parameters

Initial Parameters
These parameters only affect the driver when it starts.
frame_id (str, default: node name)
  • Frame of reference ID for coordinate transforms
auto_exposure (int, default: 1)
  • -1 leaves in current state; 0 turns off auto exposure; 1 turns it on.
integration_time (int, default: -1)
  • Sets integration time [SR3k:(integration_time+1)*0.200 ms; SR4k 0.300ms+(integration_time)*0.100 ms]. -1 leaves in current state; should not be used with auto_exposure.
modulation_freq (int, default: -1)
  • Set modulation frequency. -1 leaves in current state (which on power up, is the FACTORY CALIBRATED state -- you probably want this one); 0 == 40MHz, SR3k: maximal range 3.75m; 1 == 30MHz, SR3k, SR4k: maximal range 5m; 2 == 21MHz, SR3k: maximal range 7.14m; 3 == 20MHz, SR3k: maximal range 7.5m; 4 == 19MHz, SR3k: maximal range 7.89m; 5 == 60MHz, SR4k: maximal range 2.5m; 6 == 15MHz, SR4k: maximal range 10m; 7 == 10MHz, SR4k: maximal range 15m; 8 == 29MHz, SR4k: maximal range 5.17m; 9 == 31MHz, SR4k: maximal range 4.84m; 10 == 14.5MHz, SR4k: maximal range 10.34m; 11 == 15.5MHz, SR4k: maximal range 9.68m
amp_threshold (int, default: -1)
  • Sets measurements with amplitude values less than this threshold to 0.
Reconfigurable Parameters
Currently no reconfigurable parameters.
Calibration Parameters
camera_info_manager/url (str, default: "")
  • URL for loading and storing calibration data in the form file:///path/to/local/calibration_file.yaml. If not specified, no data will be loaded, and calibration data will be stored in file:///tmp/calibration_<camera_name>.yaml.

Wiki: sr4k (last edited 2010-05-05 10:21:30 by MarcKillpack)