Recent updates changed the published point cloud frame of reference to be the same one used by stereo_image_proc (+x is right, +y is down, +z is forward). This was meant to help beginning users validate the SR data versus a stereo setup.
ROS API
swissranger_camera
The swissranger_camera driver provides a ROS interface for Mesa Imaging SwissRanger devices (3000/4000/4500) that use the libmesasr libraries.Published Topics
camera_info (sensor_msgs/CameraInfo)- Camera intrinsics for published images
- 2D depth image
- 2D intensity image that corresponds to the depth image of distance/image_raw
- 3D pointcloud generated from distance/image_raw
Services
set_camera_info (sensor_msgs/SetCameraInfo)- Sets the camera's calibration
Parameters
Initial Parameters
These parameters only affect the driver when it starts.- Frame of reference ID for coordinate transforms
- -1 leaves in current state; 0 turns off auto exposure; 1 turns it on.
- 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.
- 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
- Sets measurements with amplitude values less than this threshold to 0.
Reconfigurable Parameters
Currently no reconfigurable parameters.Calibration Parameters
- 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.