ROS device driver for the scanCONTROL series of laser line scanners of Micro Epsilon using the scanCONTROL Linux C++ SDK 0.2. The driver allows to connect to a (specific) scanCONTROL device, configure the sensor using predefined settings or at runtime and publishes the sensor data as point clouds.
Author: D. Kroezen (GitHub username: dave992)
Affiliation: SAM|XL, TU Delft
Maintainer: D. Kroezen, d.kroezen@tudelft.nl
The micro_epsilon_scancontrol package has been tested under ROS Melodic and Ubuntu 18.04.
To build from source, clone the latest version from this repository into your catkin workspace and compile the package using:
cd catkin_ws/src
git clone https://github.com/sam-xl/micro_epsilon_scancontrol.git
cd ../
catkin build
Run the main driver node with:
roslaunch micro_epsilon_scancontrol_driver load_driver.launch
- driver.launch: Launch a single scanCONTROL driver node and the configuration window.
The scancontrol_driver_node connects to the scanCONTROL device and allows control of most settings through the provided services. By default the driver only extracts the xyz data from the measurement buffer to create the point cloud message. For now the additional measurement data such as reflections are discarted.
-
/scancontrol_pointcloud
(sensor_msgs/PointCloud2)The laser scan data filtered by the partial profile settings. The last point(s) may get lost, as a timestamp overwrites the last 4 bytes of the measurement buffer.
Most servives are wrappers of the scanCONTROL API. For more information on the available settings and values see the documentation as part of the scanCONTROL Linux C++ SDK 0.2. The rqt plugin uses these services to change the settings during runtime.
-
~set_feature
(micro_epsilon_scancontrol_msgs/SetFeature)Set a feature (setting) on the scanCONTROL device.
-
~get_feature
(micro_epsilon_scancontrol_msgs/GetFeature)Get the current feature (setting) from the connected scanCONTROL device.
-
~get_resolution
(micro_epsilon_scancontrol_msgs/GetResolution)Get the current active resolution used by the connected scanCONTROL device.
-
~set_resolution
(micro_epsilon_scancontrol_msgs/SetResolution)Set the resultion of the connected scanCONTROL device.
-
~get_available_resolutions
(micro_epsilon_scancontrol_msgs/GetAvailableResolutions)Retrieve a list of all available resolutions of the connected scanCONTROL device.
-
~invert_x
(std_srvs/SetBool)Flip the X values around the middle of the laser line of the sensor.
-
~invert_z
(std_srvs/SetBoolFlip the Z values around the middle of the measuring range of the sensor. Factory default value of of this setting is
True
.
Device Settings
-
resolution
(int)Define a prefered resolution setting for the laser scan. By default the highest available resolution is selected.
The following parameters are available to allow using multiple scanCONTROL devices.
-
serial
(string)Define a prefered scanCONTROL device by its serial number. If not defined, the driver will try to connect to the first device it is able to find.
-
topic_name
(string, default:scancontrol_pointcloud
)Define a custom name for the topic to publish the point cloud data on.
-
frame_id
(string, default:scancontrol
)Define a custom name for the measurement frame in which the point clouds are published.
Encapsulates the same driver class as the scancontrol_driver_node, but instead allows for zero-copy data transfer. The Topics, services and paremeters are the same as described for the scancontrol_driver_node above.
Please report bugs and request features using the Issue Tracker.