# Blickfeld ROS package This package provides ROS node and nodelet for publishing PointCloud2 messages from Blickfeld LiDAR devices. The driver is available under https://www.blickfeld.com/resources ## Supported devices The Blickfeld ROS driver supports the Blickfeld Cube 1, Cube 1 Outdoor, and Cube Range 1. ## Supported ROS Distributions The Blickfeld ROS driver supports the following ROS distributions - ROS Melodic Morenia (Ubuntu 18.04) - ROS Noetic Ninjemys (Ubuntu 20.04) ## Dependencies Please install the following dependencies on your system in advance. - [blickfeld-scanner-library (BSL) ](https://docs.blickfeld.com/cube/latest/external/blickfeld-scanner-lib/install.html) with system-wide protobuf installation. Minimum required version is **BSL Version 2.18.2** - [ROS Melodic Installation](http://wiki.ros.org/melodic/Installation/Ubuntu) with Ubuntu 18.04 **OR** [ROS Noetic Installation](http://wiki.ros.org/noetic/Installation/Ubuntu) with Ubuntu 20.04 - [diagnostic_updater](https://index.ros.org/p/diagnostic_updater/) can be acquired via your distribution's package manager, ${ROS_DISTRO} should be your ROS version. (e.g. melodic or noetic) $ sudo apt install ros-${ROS_DISTRO}-diagnostic-updater $ sudo apt install ros-${ROS_DISTRO}-diagnostic-msgs or via $ rosdep update $ rosdep install --from-paths src --ignore-src -r -y - [catkin](https://catkin-tools.readthedocs.io/en/latest/installing.html): required for building the workspace ## Build Before building, please source your ROS distribution. You will need to run this command on every new shell you open to have access to the ROS commands. ${ROS_DISTRO} should be your ROS version. (melodic or noetic) $ source /opt/ros/${ROS_DISTRO}/setup.bash Create your catkin workspace: $ mkdir -p ${catkin_workspace}/src where ${catkin_workspace} is your custom directory. Move the ros_blickfeld_driver package into the {catkin_workspace}/src directory and build your workspace: $ cd ${catkin_workspace} $ catkin build You may use `catkin_make` instead of `catkin build` as well. ## Running the Blickfeld ROS node You can start the Blickfeld driver as either node or nodelet. You can use the `live_scanner.launch` launch file for node. And `live_scanner_nodelet.launch` for nodelet. You can launch the ROS driver in a **DHCP** controlled network by providing the Hostname of the Cube sensor (you can check and set the Hostname in the WebGUI of the device). E.g, cube-XXXXXXXXX, where XXXXXXXXX must be replaced by the 9-digit serial number of the Cube. $ roslaunch blickfeld_driver live_scanner.launch host:=cube-XXXXXXXXX or respectively $ roslaunch blickfeld_driver live_scanner_nodelet.launch host:=cube-XXXXXXXXX You should now be able to see a PointCloud2 in rviz on the `/bf_lidar/points_raw` topic. To visualize the published data, run rviz. $ rviz By default we do not start rviz, set the rviz parameter to true if you want to start rviz with the Blickfeld ROS driver: $ roslaunch blickfeld_driver live_scanner.launch host:=cube-XXXXXXXXX rviz:=true See the table with all available Parameters and there default configuration. ### Parameters Both launch files have arguments you can use: | Argument | Default | Note | | ------------------------------------------------ | -------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | **host** (required) | | The hostname or the IP address of the Cube sensor you want to publish the point clouds from, e.g., `cube-XXXXXXXXX`. | | lidar_frame_id | `lidar` | The ROS TF where the point cloud should be in. | | node_name | `bf_lidar` | Name of this ROS node. | | remap | `true` | Remap this node’s input/output topics to commonly used ones.
If `false`, canonical names in the form of `$(arg node_name)/foo*(in/out)`are used, depending on whether a topic is an input or and output topic. | | rviz | `false` | Start rviz if this argument is true. | | publish_ambient_light | `false` | Set to `true` if the PointCloud2 message should contain the ambient light level. | | publish_explicit_range | `false` | Set to `true` if the PointCloud2 message should contain the`range` field. | | publish_intensities | `true` | Set to `true` if the PointCloud2 message should contain intensities. | | publish_no_return_points | `false` | Set to `true` if the PointCloud2 message should contain points with a fixed range for pulses without a return. The fixed range can be configured using the `no_return_point_range` parameter. | | publish_point_id | `true` | Outputs a frame-global id per laser pulse. If the device is configured to return multiple returns (multiple reflections) per pulse, point_id will be identical for all returns that belonged to the same laser pulse; In this case the `return_id` will differenciate the multiple returns from a laser pulse. | publish_point_time_offset | `false` | If set to `true`, the PointCloud2 message will contain the timestamp field per point, which represents the time offset from the start of the frame. | | no_return_point_range | `1.0` | Set the fixed range for points that are output despite the laser pulse did not cause a return to be detected. | | returns_publishing_options | `strongest` | Different options to publish multiple returns, possible values are: `strongest`, `closest`, `farthest`, and `all`, in case of `all`, the field `return_id` (ID for each returned point) is added to the point cloud. The `return_id` field is absent from the point cloud when the `returns_publishing_options` value is set to `strongest`, `closest` or `farthest`. | | projection_type | `angle_preserving` | Different options to project the data onto a 2D image, possible values are: `angle_preserving` or `scanline_preserving`. These indicate if a correct spherical projection is desired, or each row of the image should correspond to one scanline. | | publish_ambient_image | `false` | Set to `true` to publish an ambient light image. | | publish_intensity_image | `false` | Set to true to publish an intensity image. In case multiple return is activated in cube, intensity image is created based on strongest return. | | publish_range_image | `false` | Set to true to publish a range image. In case multiple return is activated in cube, range image is created based on strongest return. | | publish_point_id_image | `true` | Set to `true` to publish an image with point ids. This image is not meant to be visualized in rviz. | | imu_acceleration_unit | `g` | Different imu acceleration units: `g`, `meters_per_second_squared`. | | publish_imu | `false` | Set to `true` to publish IMU data in burst mode. | | publish_imu_static_tf_at_start | `false` | Call "Publish IMU tf transform" service once at the beginning. This service publishes the IMU data from device as static TF transformation. | | use_lidar_timestamp | `true` | Set to `true` if the timestamp in the ROS point cloud message should be generated from the device timestamp; otherwise the timestamp will represent the ROS time when the frame was received on ROS. | | use_background_subtraction | `false` | Enables on-device background subtraction. | | use_neighbor_filter | `false` | Enables on-device neighbor filter. | | background_subtraction_exponential_decay_rate | `0.005` | Exponential decay factor. Controls how fast objects switch between foreground and background when background subtraction is enabled. | | background_subtraction_num_initialization_frames | `10` | Number of frames to initialize the background with. | | ambient_image_out | `$(arg node_name)/ambient_image_out` | Topic to publish the ambient image on. | | diagnostic_out | `$(arg node_name)/diagnostic` | Topic to publish the diagnostic status. | | imu_out | `$(arg node_name)/imu` | Topic to publish the IMU burst data. | | intensity_image_out | `$(arg node_name)/intensity_image_out` | Topic to publish the intensity image on. | | point_cloud_out | `$(arg node_name)/points_raw` | Topic to publish the PointCloud2 message to. | | range_image_out | `$(arg node_name)/range_image_out` | Topic to publish the range image on. | | point_id_image | `$(arg node_name)/point_id_image` | Topic to publish the point id image on. | ## Services The Blickfeld ROS driver advertises different services. ### Set scan pattern This service call will set scan pattern on a device. e.g. `rosservice call /bf_lidar/set_scan_pattern "{fov_horizontal: 72.0, fov_vertical: 30.0, angle_spacing: 0.4, scanlines_up: 28, scanlines_down: 28, frame_mode: 'COMBINE_UP_DOWN', pulse_type: 'INTERLEAVE'}" ` ### Publish IMU tf transform This service call will receive the static IMU data from device and creates a frame from the data with the frame_id `$(arg lidar_frame_id)_imu`. `rosservice call /$(arg node_name)/publish_imu_static_tf ` ## License This package is released under a [BSD 3-Clause License](LICENSE) (see also [https://opensource.org/licenses/BSD-3-Clause](https://opensource.org/licenses/BSD-3-Clause))